diff --git a/MAVSDK_SERVER_VERSION b/MAVSDK_SERVER_VERSION index 5bd9725a..eaf8bae7 100644 --- a/MAVSDK_SERVER_VERSION +++ b/MAVSDK_SERVER_VERSION @@ -1 +1 @@ -v0.25.0 +v0.26.0 diff --git a/mavsdk/generated/calibration.py b/mavsdk/generated/calibration.py index 1f5f3cf9..0b685be0 100644 --- a/mavsdk/generated/calibration.py +++ b/mavsdk/generated/calibration.py @@ -56,6 +56,9 @@ class Result(Enum): CANCELLED Calibration process was cancelled + FAILED_ARMED + Calibration process failed since the vehicle is armed + """ @@ -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: @@ -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): @@ -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 @@ -401,7 +409,7 @@ async def calibrate_accelerometer(self): async def calibrate_magnetometer(self): """ - Perform magnetometer caliration. + Perform magnetometer calibration. Yields ------- @@ -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. diff --git a/mavsdk/generated/calibration_pb2.py b/mavsdk/generated/calibration_pb2.py index add12118..7f4c4314 100644 --- a/mavsdk/generated/calibration_pb2.py +++ b/mavsdk/generated/calibration_pb2.py @@ -19,7 +19,7 @@ package='mavsdk.rpc.calibration', syntax='proto3', serialized_options=b'\n\025io.mavsdk.calibrationB\020CalibrationProto', - serialized_pb=b'\n\x11\x63\x61libration.proto\x12\x16mavsdk.rpc.calibration\x1a\x14mavsdk_options.proto\"\x1f\n\x1dSubscribeCalibrateGyroRequest\"\x9b\x01\n\x15\x43\x61librateGyroResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"(\n&SubscribeCalibrateAccelerometerRequest\"\xa4\x01\n\x1e\x43\x61librateAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\'\n%SubscribeCalibrateMagnetometerRequest\"\xa3\x01\n\x1d\x43\x61librateMagnetometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\".\n,SubscribeCalibrateGimbalAccelerometerRequest\"\xaa\x01\n$CalibrateGimbalAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\x0f\n\rCancelRequest\"\x10\n\x0e\x43\x61ncelResponse\"\xc9\x02\n\x11\x43\x61librationResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.calibration.CalibrationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xdd\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x11\n\rRESULT_FAILED\x10\x03\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x0f\n\x0bRESULT_BUSY\x10\x06\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12\x14\n\x10RESULT_CANCELLED\x10\t\"\x83\x01\n\x0cProgressData\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x0fhas_status_text\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x13\n\x0bstatus_text\x18\x04 \x01(\t2\x87\x06\n\x12\x43\x61librationService\x12\x8a\x01\n\x16SubscribeCalibrateGyro\x12\x35.mavsdk.rpc.calibration.SubscribeCalibrateGyroRequest\x1a-.mavsdk.rpc.calibration.CalibrateGyroResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa5\x01\n\x1fSubscribeCalibrateAccelerometer\x12>.mavsdk.rpc.calibration.SubscribeCalibrateAccelerometerRequest\x1a\x36.mavsdk.rpc.calibration.CalibrateAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateMagnetometer\x12=.mavsdk.rpc.calibration.SubscribeCalibrateMagnetometerRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateMagnetometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xb7\x01\n%SubscribeCalibrateGimbalAccelerometer\x12\x44.mavsdk.rpc.calibration.SubscribeCalibrateGimbalAccelerometerRequest\x1a<.mavsdk.rpc.calibration.CalibrateGimbalAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12]\n\x06\x43\x61ncel\x12%.mavsdk.rpc.calibration.CancelRequest\x1a&.mavsdk.rpc.calibration.CancelResponse\"\x04\x80\xb5\x18\x01\x42)\n\x15io.mavsdk.calibrationB\x10\x43\x61librationProtob\x06proto3' + serialized_pb=b'\n\x11\x63\x61libration.proto\x12\x16mavsdk.rpc.calibration\x1a\x14mavsdk_options.proto\"\x1f\n\x1dSubscribeCalibrateGyroRequest\"\x9b\x01\n\x15\x43\x61librateGyroResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"(\n&SubscribeCalibrateAccelerometerRequest\"\xa4\x01\n\x1e\x43\x61librateAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\'\n%SubscribeCalibrateMagnetometerRequest\"\xa3\x01\n\x1d\x43\x61librateMagnetometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\'\n%SubscribeCalibrateLevelHorizonRequest\"\xa3\x01\n\x1d\x43\x61librateLevelHorizonResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\".\n,SubscribeCalibrateGimbalAccelerometerRequest\"\xaa\x01\n$CalibrateGimbalAccelerometerResponse\x12\x45\n\x12\x63\x61libration_result\x18\x01 \x01(\x0b\x32).mavsdk.rpc.calibration.CalibrationResult\x12;\n\rprogress_data\x18\x02 \x01(\x0b\x32$.mavsdk.rpc.calibration.ProgressData\"\x0f\n\rCancelRequest\"\x10\n\x0e\x43\x61ncelResponse\"\xe2\x02\n\x11\x43\x61librationResult\x12@\n\x06result\x18\x01 \x01(\x0e\x32\x30.mavsdk.rpc.calibration.CalibrationResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xf6\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x11\n\rRESULT_FAILED\x10\x03\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x04\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x05\x12\x0f\n\x0bRESULT_BUSY\x10\x06\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x07\x12\x12\n\x0eRESULT_TIMEOUT\x10\x08\x12\x14\n\x10RESULT_CANCELLED\x10\t\x12\x17\n\x13RESULT_FAILED_ARMED\x10\n\"\x83\x01\n\x0cProgressData\x12\x1f\n\x0chas_progress\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x19\n\x08progress\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x0fhas_status_text\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x13\n\x0bstatus_text\x18\x04 \x01(\t2\xac\x07\n\x12\x43\x61librationService\x12\x8a\x01\n\x16SubscribeCalibrateGyro\x12\x35.mavsdk.rpc.calibration.SubscribeCalibrateGyroRequest\x1a-.mavsdk.rpc.calibration.CalibrateGyroResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa5\x01\n\x1fSubscribeCalibrateAccelerometer\x12>.mavsdk.rpc.calibration.SubscribeCalibrateAccelerometerRequest\x1a\x36.mavsdk.rpc.calibration.CalibrateAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateMagnetometer\x12=.mavsdk.rpc.calibration.SubscribeCalibrateMagnetometerRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateMagnetometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xa2\x01\n\x1eSubscribeCalibrateLevelHorizon\x12=.mavsdk.rpc.calibration.SubscribeCalibrateLevelHorizonRequest\x1a\x35.mavsdk.rpc.calibration.CalibrateLevelHorizonResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\xb7\x01\n%SubscribeCalibrateGimbalAccelerometer\x12\x44.mavsdk.rpc.calibration.SubscribeCalibrateGimbalAccelerometerRequest\x1a<.mavsdk.rpc.calibration.CalibrateGimbalAccelerometerResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12]\n\x06\x43\x61ncel\x12%.mavsdk.rpc.calibration.CancelRequest\x1a&.mavsdk.rpc.calibration.CancelResponse\"\x04\x80\xb5\x18\x01\x42)\n\x15io.mavsdk.calibrationB\x10\x43\x61librationProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -71,11 +71,15 @@ name='RESULT_CANCELLED', index=9, number=9, serialized_options=None, type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_FAILED_ARMED', index=10, number=10, + serialized_options=None, + type=None), ], containing_type=None, serialized_options=None, - serialized_start=1039, - serialized_end=1260, + serialized_start=1246, + serialized_end=1492, ) _sym_db.RegisterEnumDescriptor(_CALIBRATIONRESULT_RESULT) @@ -266,6 +270,68 @@ ) +_SUBSCRIBECALIBRATELEVELHORIZONREQUEST = _descriptor.Descriptor( + name='SubscribeCalibrateLevelHorizonRequest', + full_name='mavsdk.rpc.calibration.SubscribeCalibrateLevelHorizonRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=674, + serialized_end=713, +) + + +_CALIBRATELEVELHORIZONRESPONSE = _descriptor.Descriptor( + name='CalibrateLevelHorizonResponse', + full_name='mavsdk.rpc.calibration.CalibrateLevelHorizonResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='calibration_result', full_name='mavsdk.rpc.calibration.CalibrateLevelHorizonResponse.calibration_result', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='progress_data', full_name='mavsdk.rpc.calibration.CalibrateLevelHorizonResponse.progress_data', index=1, + number=2, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=716, + serialized_end=879, +) + + _SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST = _descriptor.Descriptor( name='SubscribeCalibrateGimbalAccelerometerRequest', full_name='mavsdk.rpc.calibration.SubscribeCalibrateGimbalAccelerometerRequest', @@ -285,8 +351,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=674, - serialized_end=720, + serialized_start=881, + serialized_end=927, ) @@ -323,8 +389,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=723, - serialized_end=893, + serialized_start=930, + serialized_end=1100, ) @@ -347,8 +413,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=895, - serialized_end=910, + serialized_start=1102, + serialized_end=1117, ) @@ -371,8 +437,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=912, - serialized_end=928, + serialized_start=1119, + serialized_end=1135, ) @@ -410,8 +476,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=931, - serialized_end=1260, + serialized_start=1138, + serialized_end=1492, ) @@ -462,8 +528,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1263, - serialized_end=1394, + serialized_start=1495, + serialized_end=1626, ) _CALIBRATEGYRORESPONSE.fields_by_name['calibration_result'].message_type = _CALIBRATIONRESULT @@ -472,6 +538,8 @@ _CALIBRATEACCELEROMETERRESPONSE.fields_by_name['progress_data'].message_type = _PROGRESSDATA _CALIBRATEMAGNETOMETERRESPONSE.fields_by_name['calibration_result'].message_type = _CALIBRATIONRESULT _CALIBRATEMAGNETOMETERRESPONSE.fields_by_name['progress_data'].message_type = _PROGRESSDATA +_CALIBRATELEVELHORIZONRESPONSE.fields_by_name['calibration_result'].message_type = _CALIBRATIONRESULT +_CALIBRATELEVELHORIZONRESPONSE.fields_by_name['progress_data'].message_type = _PROGRESSDATA _CALIBRATEGIMBALACCELEROMETERRESPONSE.fields_by_name['calibration_result'].message_type = _CALIBRATIONRESULT _CALIBRATEGIMBALACCELEROMETERRESPONSE.fields_by_name['progress_data'].message_type = _PROGRESSDATA _CALIBRATIONRESULT.fields_by_name['result'].enum_type = _CALIBRATIONRESULT_RESULT @@ -482,6 +550,8 @@ DESCRIPTOR.message_types_by_name['CalibrateAccelerometerResponse'] = _CALIBRATEACCELEROMETERRESPONSE DESCRIPTOR.message_types_by_name['SubscribeCalibrateMagnetometerRequest'] = _SUBSCRIBECALIBRATEMAGNETOMETERREQUEST DESCRIPTOR.message_types_by_name['CalibrateMagnetometerResponse'] = _CALIBRATEMAGNETOMETERRESPONSE +DESCRIPTOR.message_types_by_name['SubscribeCalibrateLevelHorizonRequest'] = _SUBSCRIBECALIBRATELEVELHORIZONREQUEST +DESCRIPTOR.message_types_by_name['CalibrateLevelHorizonResponse'] = _CALIBRATELEVELHORIZONRESPONSE DESCRIPTOR.message_types_by_name['SubscribeCalibrateGimbalAccelerometerRequest'] = _SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST DESCRIPTOR.message_types_by_name['CalibrateGimbalAccelerometerResponse'] = _CALIBRATEGIMBALACCELEROMETERRESPONSE DESCRIPTOR.message_types_by_name['CancelRequest'] = _CANCELREQUEST @@ -532,6 +602,20 @@ }) _sym_db.RegisterMessage(CalibrateMagnetometerResponse) +SubscribeCalibrateLevelHorizonRequest = _reflection.GeneratedProtocolMessageType('SubscribeCalibrateLevelHorizonRequest', (_message.Message,), { + 'DESCRIPTOR' : _SUBSCRIBECALIBRATELEVELHORIZONREQUEST, + '__module__' : 'calibration_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.calibration.SubscribeCalibrateLevelHorizonRequest) + }) +_sym_db.RegisterMessage(SubscribeCalibrateLevelHorizonRequest) + +CalibrateLevelHorizonResponse = _reflection.GeneratedProtocolMessageType('CalibrateLevelHorizonResponse', (_message.Message,), { + 'DESCRIPTOR' : _CALIBRATELEVELHORIZONRESPONSE, + '__module__' : 'calibration_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.calibration.CalibrateLevelHorizonResponse) + }) +_sym_db.RegisterMessage(CalibrateLevelHorizonResponse) + SubscribeCalibrateGimbalAccelerometerRequest = _reflection.GeneratedProtocolMessageType('SubscribeCalibrateGimbalAccelerometerRequest', (_message.Message,), { 'DESCRIPTOR' : _SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST, '__module__' : 'calibration_pb2' @@ -586,8 +670,8 @@ file=DESCRIPTOR, index=0, serialized_options=None, - serialized_start=1397, - serialized_end=2172, + serialized_start=1629, + serialized_end=2569, methods=[ _descriptor.MethodDescriptor( name='SubscribeCalibrateGyro', @@ -616,10 +700,19 @@ output_type=_CALIBRATEMAGNETOMETERRESPONSE, serialized_options=b'\200\265\030\000\210\265\030\001', ), + _descriptor.MethodDescriptor( + name='SubscribeCalibrateLevelHorizon', + full_name='mavsdk.rpc.calibration.CalibrationService.SubscribeCalibrateLevelHorizon', + index=3, + containing_service=None, + input_type=_SUBSCRIBECALIBRATELEVELHORIZONREQUEST, + output_type=_CALIBRATELEVELHORIZONRESPONSE, + serialized_options=b'\200\265\030\000\210\265\030\001', + ), _descriptor.MethodDescriptor( name='SubscribeCalibrateGimbalAccelerometer', full_name='mavsdk.rpc.calibration.CalibrationService.SubscribeCalibrateGimbalAccelerometer', - index=3, + index=4, containing_service=None, input_type=_SUBSCRIBECALIBRATEGIMBALACCELEROMETERREQUEST, output_type=_CALIBRATEGIMBALACCELEROMETERRESPONSE, @@ -628,7 +721,7 @@ _descriptor.MethodDescriptor( name='Cancel', full_name='mavsdk.rpc.calibration.CalibrationService.Cancel', - index=4, + index=5, containing_service=None, input_type=_CANCELREQUEST, output_type=_CANCELRESPONSE, diff --git a/mavsdk/generated/calibration_pb2_grpc.py b/mavsdk/generated/calibration_pb2_grpc.py index f5e77adc..8d626de2 100644 --- a/mavsdk/generated/calibration_pb2_grpc.py +++ b/mavsdk/generated/calibration_pb2_grpc.py @@ -29,6 +29,11 @@ def __init__(self, channel): request_serializer=calibration__pb2.SubscribeCalibrateMagnetometerRequest.SerializeToString, response_deserializer=calibration__pb2.CalibrateMagnetometerResponse.FromString, ) + self.SubscribeCalibrateLevelHorizon = channel.unary_stream( + '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon', + request_serializer=calibration__pb2.SubscribeCalibrateLevelHorizonRequest.SerializeToString, + response_deserializer=calibration__pb2.CalibrateLevelHorizonResponse.FromString, + ) self.SubscribeCalibrateGimbalAccelerometer = channel.unary_stream( '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateGimbalAccelerometer', request_serializer=calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.SerializeToString, @@ -60,7 +65,14 @@ def SubscribeCalibrateAccelerometer(self, request, context): raise NotImplementedError('Method not implemented!') def SubscribeCalibrateMagnetometer(self, request, context): - """Perform magnetometer caliration. + """Perform magnetometer calibration. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def SubscribeCalibrateLevelHorizon(self, request, context): + """Perform board level horizon calibration. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) context.set_details('Method not implemented!') @@ -98,6 +110,11 @@ def add_CalibrationServiceServicer_to_server(servicer, server): request_deserializer=calibration__pb2.SubscribeCalibrateMagnetometerRequest.FromString, response_serializer=calibration__pb2.CalibrateMagnetometerResponse.SerializeToString, ), + 'SubscribeCalibrateLevelHorizon': grpc.unary_stream_rpc_method_handler( + servicer.SubscribeCalibrateLevelHorizon, + request_deserializer=calibration__pb2.SubscribeCalibrateLevelHorizonRequest.FromString, + response_serializer=calibration__pb2.CalibrateLevelHorizonResponse.SerializeToString, + ), 'SubscribeCalibrateGimbalAccelerometer': grpc.unary_stream_rpc_method_handler( servicer.SubscribeCalibrateGimbalAccelerometer, request_deserializer=calibration__pb2.SubscribeCalibrateGimbalAccelerometerRequest.FromString, @@ -167,6 +184,22 @@ def SubscribeCalibrateMagnetometer(request, options, channel_credentials, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def SubscribeCalibrateLevelHorizon(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.calibration.CalibrationService/SubscribeCalibrateLevelHorizon', + calibration__pb2.SubscribeCalibrateLevelHorizonRequest.SerializeToString, + calibration__pb2.CalibrateLevelHorizonResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def SubscribeCalibrateGimbalAccelerometer(request, target, diff --git a/proto b/proto index 6dfc9096..4d8697ef 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 6dfc90966e782ee7faf55f620f2cb7d1b736d79d +Subproject commit 4d8697eff611ec89dfaf62358aef1cf60d423bb5