diff --git a/MAVSDK_SERVER_VERSION b/MAVSDK_SERVER_VERSION index fe2b5349..c4041f14 100644 --- a/MAVSDK_SERVER_VERSION +++ b/MAVSDK_SERVER_VERSION @@ -1,4 +1,4 @@ -v0.35.1 +v0.36.0 diff --git a/mavsdk/gimbal.py b/mavsdk/gimbal.py index 451bbc13..f1000799 100644 --- a/mavsdk/gimbal.py +++ b/mavsdk/gimbal.py @@ -42,6 +42,172 @@ def __str__(self): return self.name +class ControlMode(Enum): + """ + Control mode + + Values + ------ + NONE + Indicates that the component does not have control over the gimbal + + PRIMARY + To take primary control over the gimbal + + SECONDARY + To take secondary control over the gimbal + + """ + + + NONE = 0 + PRIMARY = 1 + SECONDARY = 2 + + def translate_to_rpc(self): + if self == ControlMode.NONE: + return gimbal_pb2.CONTROL_MODE_NONE + if self == ControlMode.PRIMARY: + return gimbal_pb2.CONTROL_MODE_PRIMARY + if self == ControlMode.SECONDARY: + return gimbal_pb2.CONTROL_MODE_SECONDARY + + @staticmethod + def translate_from_rpc(rpc_enum_value): + """ Parses a gRPC response """ + if rpc_enum_value == gimbal_pb2.CONTROL_MODE_NONE: + return ControlMode.NONE + if rpc_enum_value == gimbal_pb2.CONTROL_MODE_PRIMARY: + return ControlMode.PRIMARY + if rpc_enum_value == gimbal_pb2.CONTROL_MODE_SECONDARY: + return ControlMode.SECONDARY + + def __str__(self): + return self.name + + +class ControlStatus: + """ + Control status + + Parameters + ---------- + control_mode : ControlMode + Control mode (none, primary or secondary) + + sysid_primary_control : int32_t + Sysid of the component that has primary control over the gimbal (0 if no one is in control) + + compid_primary_control : int32_t + Compid of the component that has primary control over the gimbal (0 if no one is in control) + + sysid_secondary_control : int32_t + Sysid of the component that has secondary control over the gimbal (0 if no one is in control) + + compid_secondary_control : int32_t + Compid of the component that has secondary control over the gimbal (0 if no one is in control) + + """ + + + + def __init__( + self, + control_mode, + sysid_primary_control, + compid_primary_control, + sysid_secondary_control, + compid_secondary_control): + """ Initializes the ControlStatus object """ + self.control_mode = control_mode + self.sysid_primary_control = sysid_primary_control + self.compid_primary_control = compid_primary_control + self.sysid_secondary_control = sysid_secondary_control + self.compid_secondary_control = compid_secondary_control + + def __equals__(self, to_compare): + """ Checks if two ControlStatus are the same """ + try: + # Try to compare - this likely fails when it is compared to a non + # ControlStatus object + return \ + (self.control_mode == to_compare.control_mode) and \ + (self.sysid_primary_control == to_compare.sysid_primary_control) and \ + (self.compid_primary_control == to_compare.compid_primary_control) and \ + (self.sysid_secondary_control == to_compare.sysid_secondary_control) and \ + (self.compid_secondary_control == to_compare.compid_secondary_control) + + except AttributeError: + return False + + def __str__(self): + """ ControlStatus in string representation """ + struct_repr = ", ".join([ + "control_mode: " + str(self.control_mode), + "sysid_primary_control: " + str(self.sysid_primary_control), + "compid_primary_control: " + str(self.compid_primary_control), + "sysid_secondary_control: " + str(self.sysid_secondary_control), + "compid_secondary_control: " + str(self.compid_secondary_control) + ]) + + return f"ControlStatus: [{struct_repr}]" + + @staticmethod + def translate_from_rpc(rpcControlStatus): + """ Translates a gRPC struct to the SDK equivalent """ + return ControlStatus( + + ControlMode.translate_from_rpc(rpcControlStatus.control_mode), + + + rpcControlStatus.sysid_primary_control, + + + rpcControlStatus.compid_primary_control, + + + rpcControlStatus.sysid_secondary_control, + + + rpcControlStatus.compid_secondary_control + ) + + def translate_to_rpc(self, rpcControlStatus): + """ Translates this SDK object into its gRPC equivalent """ + + + + + rpcControlStatus.control_mode = self.control_mode.translate_to_rpc() + + + + + + rpcControlStatus.sysid_primary_control = self.sysid_primary_control + + + + + + rpcControlStatus.compid_primary_control = self.compid_primary_control + + + + + + rpcControlStatus.sysid_secondary_control = self.sysid_secondary_control + + + + + + rpcControlStatus.compid_secondary_control = self.compid_secondary_control + + + + + class GimbalResult: """ Result type. @@ -243,6 +409,40 @@ async def set_pitch_and_yaw(self, pitch_deg, yaw_deg): raise GimbalError(result, "set_pitch_and_yaw()", pitch_deg, yaw_deg) + async def set_pitch_rate_and_yaw_rate(self, pitch_rate_deg_s, yaw_rate_deg_s): + """ + Set gimbal angular rates around pitch and yaw axes. + + This sets the desired angular rates around pitch and yaw axes of a gimbal. + Will return when the command is accepted, however, it might + take the gimbal longer to actually reach the angular rate. + + Parameters + ---------- + pitch_rate_deg_s : float + Angular rate around pitch axis in degrees/second (negative downward) + + yaw_rate_deg_s : float + Angular rate around yaw axis in degrees/second (positive is clock-wise) + + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. + """ + + request = gimbal_pb2.SetPitchRateAndYawRateRequest() + request.pitch_rate_deg_s = pitch_rate_deg_s + request.yaw_rate_deg_s = yaw_rate_deg_s + response = await self._stub.SetPitchRateAndYawRate(request) + + + result = self._extract_result(response) + + if result.result is not GimbalResult.Result.SUCCESS: + raise GimbalError(result, "set_pitch_rate_and_yaw_rate()", pitch_rate_deg_s, yaw_rate_deg_s) + + async def set_mode(self, gimbal_mode): """ Set gimbal mode. @@ -314,4 +514,91 @@ async def set_roi_location(self, latitude_deg, longitude_deg, altitude_m): if result.result is not GimbalResult.Result.SUCCESS: raise GimbalError(result, "set_roi_location()", latitude_deg, longitude_deg, altitude_m) - \ No newline at end of file + + + async def take_control(self, control_mode): + """ + Take control. + + There can be only two components in control of a gimbal at any given time. + One with "primary" control, and one with "secondary" control. The way the + secondary control is implemented is not specified and hence depends on the + vehicle. + + Components are expected to be cooperative, which means that they can + override each other and should therefore do it carefully. + + Parameters + ---------- + control_mode : ControlMode + Control mode (primary or secondary) + + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. + """ + + request = gimbal_pb2.TakeControlRequest() + + request.control_mode = control_mode.translate_to_rpc() + + + response = await self._stub.TakeControl(request) + + + result = self._extract_result(response) + + if result.result is not GimbalResult.Result.SUCCESS: + raise GimbalError(result, "take_control()", control_mode) + + + async def release_control(self): + """ + Release control. + + Release control, such that other components can control the gimbal. + + Raises + ------ + GimbalError + If the request fails. The error contains the reason for the failure. + """ + + request = gimbal_pb2.ReleaseControlRequest() + response = await self._stub.ReleaseControl(request) + + + result = self._extract_result(response) + + if result.result is not GimbalResult.Result.SUCCESS: + raise GimbalError(result, "release_control()") + + + async def control(self): + """ + Subscribe to control status updates. + + This allows a component to know if it has primary, secondary or + no control over the gimbal. Also, it gives the system and component ids + of the other components in control (if any). + + Yields + ------- + control_status : ControlStatus + Control status + + + """ + + request = gimbal_pb2.SubscribeControlRequest() + control_stream = self._stub.SubscribeControl(request) + + try: + async for response in control_stream: + + + + yield ControlStatus.translate_from_rpc(response.control_status) + finally: + control_stream.cancel() \ No newline at end of file diff --git a/mavsdk/gimbal_pb2.py b/mavsdk/gimbal_pb2.py index 1a6cf128..94f8dda4 100644 --- a/mavsdk/gimbal_pb2.py +++ b/mavsdk/gimbal_pb2.py @@ -20,7 +20,7 @@ syntax='proto3', serialized_options=b'\n\020io.mavsdk.gimbalB\013GimbalProto', create_key=_descriptor._internal_create_key, - serialized_pb=b'\n\x13gimbal/gimbal.proto\x12\x11mavsdk.rpc.gimbal\";\n\x15SetPitchAndYawRequest\x12\x11\n\tpitch_deg\x18\x01 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x02 \x01(\x02\"P\n\x16SetPitchAndYawResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"D\n\x0eSetModeRequest\x12\x32\n\x0bgimbal_mode\x18\x01 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\"I\n\x0fSetModeResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"X\n\x15SetRoiLocationRequest\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x12\n\naltitude_m\x18\x03 \x01(\x02\"P\n\x16SetRoiLocationResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"\xca\x01\n\x0cGimbalResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.gimbal.GimbalResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"n\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x10\n\x0cRESULT_ERROR\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x04*B\n\nGimbalMode\x12\x1a\n\x16GIMBAL_MODE_YAW_FOLLOW\x10\x00\x12\x18\n\x14GIMBAL_MODE_YAW_LOCK\x10\x01\x32\xb5\x02\n\rGimbalService\x12g\n\x0eSetPitchAndYaw\x12(.mavsdk.rpc.gimbal.SetPitchAndYawRequest\x1a).mavsdk.rpc.gimbal.SetPitchAndYawResponse\"\x00\x12R\n\x07SetMode\x12!.mavsdk.rpc.gimbal.SetModeRequest\x1a\".mavsdk.rpc.gimbal.SetModeResponse\"\x00\x12g\n\x0eSetRoiLocation\x12(.mavsdk.rpc.gimbal.SetRoiLocationRequest\x1a).mavsdk.rpc.gimbal.SetRoiLocationResponse\"\x00\x42\x1f\n\x10io.mavsdk.gimbalB\x0bGimbalProtob\x06proto3' + serialized_pb=b'\n\x13gimbal/gimbal.proto\x12\x11mavsdk.rpc.gimbal\";\n\x15SetPitchAndYawRequest\x12\x11\n\tpitch_deg\x18\x01 \x01(\x02\x12\x0f\n\x07yaw_deg\x18\x02 \x01(\x02\"P\n\x16SetPitchAndYawResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"Q\n\x1dSetPitchRateAndYawRateRequest\x12\x18\n\x10pitch_rate_deg_s\x18\x01 \x01(\x02\x12\x16\n\x0eyaw_rate_deg_s\x18\x02 \x01(\x02\"X\n\x1eSetPitchRateAndYawRateResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"D\n\x0eSetModeRequest\x12\x32\n\x0bgimbal_mode\x18\x01 \x01(\x0e\x32\x1d.mavsdk.rpc.gimbal.GimbalMode\"I\n\x0fSetModeResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"X\n\x15SetRoiLocationRequest\x12\x14\n\x0clatitude_deg\x18\x01 \x01(\x01\x12\x15\n\rlongitude_deg\x18\x02 \x01(\x01\x12\x12\n\naltitude_m\x18\x03 \x01(\x02\"P\n\x16SetRoiLocationResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"J\n\x12TakeControlRequest\x12\x34\n\x0c\x63ontrol_mode\x18\x01 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode\"M\n\x13TakeControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"\x17\n\x15ReleaseControlRequest\"P\n\x16ReleaseControlResponse\x12\x36\n\rgimbal_result\x18\x01 \x01(\x0b\x32\x1f.mavsdk.rpc.gimbal.GimbalResult\"\x19\n\x17SubscribeControlRequest\"K\n\x0f\x43ontrolResponse\x12\x38\n\x0e\x63ontrol_status\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.gimbal.ControlStatus\"\xc7\x01\n\rControlStatus\x12\x34\n\x0c\x63ontrol_mode\x18\x01 \x01(\x0e\x32\x1e.mavsdk.rpc.gimbal.ControlMode\x12\x1d\n\x15sysid_primary_control\x18\x02 \x01(\x05\x12\x1e\n\x16\x63ompid_primary_control\x18\x03 \x01(\x05\x12\x1f\n\x17sysid_secondary_control\x18\x04 \x01(\x05\x12 \n\x18\x63ompid_secondary_control\x18\x05 \x01(\x05\"\xca\x01\n\x0cGimbalResult\x12\x36\n\x06result\x18\x01 \x01(\x0e\x32&.mavsdk.rpc.gimbal.GimbalResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"n\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x10\n\x0cRESULT_ERROR\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x16\n\x12RESULT_UNSUPPORTED\x10\x04*B\n\nGimbalMode\x12\x1a\n\x16GIMBAL_MODE_YAW_FOLLOW\x10\x00\x12\x18\n\x14GIMBAL_MODE_YAW_LOCK\x10\x01*Z\n\x0b\x43ontrolMode\x12\x15\n\x11\x43ONTROL_MODE_NONE\x10\x00\x12\x18\n\x14\x43ONTROL_MODE_PRIMARY\x10\x01\x12\x1a\n\x16\x43ONTROL_MODE_SECONDARY\x10\x02\x32\xe7\x05\n\rGimbalService\x12g\n\x0eSetPitchAndYaw\x12(.mavsdk.rpc.gimbal.SetPitchAndYawRequest\x1a).mavsdk.rpc.gimbal.SetPitchAndYawResponse\"\x00\x12\x7f\n\x16SetPitchRateAndYawRate\x12\x30.mavsdk.rpc.gimbal.SetPitchRateAndYawRateRequest\x1a\x31.mavsdk.rpc.gimbal.SetPitchRateAndYawRateResponse\"\x00\x12R\n\x07SetMode\x12!.mavsdk.rpc.gimbal.SetModeRequest\x1a\".mavsdk.rpc.gimbal.SetModeResponse\"\x00\x12g\n\x0eSetRoiLocation\x12(.mavsdk.rpc.gimbal.SetRoiLocationRequest\x1a).mavsdk.rpc.gimbal.SetRoiLocationResponse\"\x00\x12^\n\x0bTakeControl\x12%.mavsdk.rpc.gimbal.TakeControlRequest\x1a&.mavsdk.rpc.gimbal.TakeControlResponse\"\x00\x12g\n\x0eReleaseControl\x12(.mavsdk.rpc.gimbal.ReleaseControlRequest\x1a).mavsdk.rpc.gimbal.ReleaseControlResponse\"\x00\x12\x66\n\x10SubscribeControl\x12*.mavsdk.rpc.gimbal.SubscribeControlRequest\x1a\".mavsdk.rpc.gimbal.ControlResponse\"\x00\x30\x01\x42\x1f\n\x10io.mavsdk.gimbalB\x0bGimbalProtob\x06proto3' ) _GIMBALMODE = _descriptor.EnumDescriptor( @@ -43,14 +43,48 @@ ], containing_type=None, serialized_options=None, - serialized_start=707, - serialized_end=773, + serialized_start=1448, + serialized_end=1514, ) _sym_db.RegisterEnumDescriptor(_GIMBALMODE) GimbalMode = enum_type_wrapper.EnumTypeWrapper(_GIMBALMODE) +_CONTROLMODE = _descriptor.EnumDescriptor( + name='ControlMode', + full_name='mavsdk.rpc.gimbal.ControlMode', + filename=None, + file=DESCRIPTOR, + create_key=_descriptor._internal_create_key, + values=[ + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_NONE', index=0, number=0, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_PRIMARY', index=1, number=1, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + _descriptor.EnumValueDescriptor( + name='CONTROL_MODE_SECONDARY', index=2, number=2, + serialized_options=None, + type=None, + create_key=_descriptor._internal_create_key), + ], + containing_type=None, + serialized_options=None, + serialized_start=1516, + serialized_end=1606, +) +_sym_db.RegisterEnumDescriptor(_CONTROLMODE) + +ControlMode = enum_type_wrapper.EnumTypeWrapper(_CONTROLMODE) GIMBAL_MODE_YAW_FOLLOW = 0 GIMBAL_MODE_YAW_LOCK = 1 +CONTROL_MODE_NONE = 0 +CONTROL_MODE_PRIMARY = 1 +CONTROL_MODE_SECONDARY = 2 _GIMBALRESULT_RESULT = _descriptor.EnumDescriptor( @@ -88,8 +122,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=595, - serialized_end=705, + serialized_start=1336, + serialized_end=1446, ) _sym_db.RegisterEnumDescriptor(_GIMBALRESULT_RESULT) @@ -165,6 +199,77 @@ ) +_SETPITCHRATEANDYAWRATEREQUEST = _descriptor.Descriptor( + name='SetPitchRateAndYawRateRequest', + full_name='mavsdk.rpc.gimbal.SetPitchRateAndYawRateRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='pitch_rate_deg_s', full_name='mavsdk.rpc.gimbal.SetPitchRateAndYawRateRequest.pitch_rate_deg_s', index=0, + number=1, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='yaw_rate_deg_s', full_name='mavsdk.rpc.gimbal.SetPitchRateAndYawRateRequest.yaw_rate_deg_s', index=1, + number=2, type=2, cpp_type=6, label=1, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=185, + serialized_end=266, +) + + +_SETPITCHRATEANDYAWRATERESPONSE = _descriptor.Descriptor( + name='SetPitchRateAndYawRateResponse', + full_name='mavsdk.rpc.gimbal.SetPitchRateAndYawRateResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='gimbal_result', full_name='mavsdk.rpc.gimbal.SetPitchRateAndYawRateResponse.gimbal_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, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=268, + serialized_end=356, +) + + _SETMODEREQUEST = _descriptor.Descriptor( name='SetModeRequest', full_name='mavsdk.rpc.gimbal.SetModeRequest', @@ -192,8 +297,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=185, - serialized_end=253, + serialized_start=358, + serialized_end=426, ) @@ -224,8 +329,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=255, - serialized_end=328, + serialized_start=428, + serialized_end=501, ) @@ -270,8 +375,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=330, - serialized_end=418, + serialized_start=503, + serialized_end=591, ) @@ -302,8 +407,246 @@ extension_ranges=[], oneofs=[ ], - serialized_start=420, - serialized_end=500, + serialized_start=593, + serialized_end=673, +) + + +_TAKECONTROLREQUEST = _descriptor.Descriptor( + name='TakeControlRequest', + full_name='mavsdk.rpc.gimbal.TakeControlRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='control_mode', full_name='mavsdk.rpc.gimbal.TakeControlRequest.control_mode', index=0, + number=1, type=14, cpp_type=8, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=675, + serialized_end=749, +) + + +_TAKECONTROLRESPONSE = _descriptor.Descriptor( + name='TakeControlResponse', + full_name='mavsdk.rpc.gimbal.TakeControlResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='gimbal_result', full_name='mavsdk.rpc.gimbal.TakeControlResponse.gimbal_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, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=751, + serialized_end=828, +) + + +_RELEASECONTROLREQUEST = _descriptor.Descriptor( + name='ReleaseControlRequest', + full_name='mavsdk.rpc.gimbal.ReleaseControlRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=830, + serialized_end=853, +) + + +_RELEASECONTROLRESPONSE = _descriptor.Descriptor( + name='ReleaseControlResponse', + full_name='mavsdk.rpc.gimbal.ReleaseControlResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='gimbal_result', full_name='mavsdk.rpc.gimbal.ReleaseControlResponse.gimbal_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, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=855, + serialized_end=935, +) + + +_SUBSCRIBECONTROLREQUEST = _descriptor.Descriptor( + name='SubscribeControlRequest', + full_name='mavsdk.rpc.gimbal.SubscribeControlRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=937, + serialized_end=962, +) + + +_CONTROLRESPONSE = _descriptor.Descriptor( + name='ControlResponse', + full_name='mavsdk.rpc.gimbal.ControlResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='control_status', full_name='mavsdk.rpc.gimbal.ControlResponse.control_status', 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, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=964, + serialized_end=1039, +) + + +_CONTROLSTATUS = _descriptor.Descriptor( + name='ControlStatus', + full_name='mavsdk.rpc.gimbal.ControlStatus', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='control_mode', full_name='mavsdk.rpc.gimbal.ControlStatus.control_mode', index=0, + number=1, type=14, cpp_type=8, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='sysid_primary_control', full_name='mavsdk.rpc.gimbal.ControlStatus.sysid_primary_control', index=1, + number=2, type=5, cpp_type=1, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='compid_primary_control', full_name='mavsdk.rpc.gimbal.ControlStatus.compid_primary_control', index=2, + number=3, type=5, cpp_type=1, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='sysid_secondary_control', full_name='mavsdk.rpc.gimbal.ControlStatus.sysid_secondary_control', index=3, + number=4, type=5, cpp_type=1, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='compid_secondary_control', full_name='mavsdk.rpc.gimbal.ControlStatus.compid_secondary_control', index=4, + number=5, type=5, cpp_type=1, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=1042, + serialized_end=1241, ) @@ -342,24 +685,40 @@ extension_ranges=[], oneofs=[ ], - serialized_start=503, - serialized_end=705, + serialized_start=1244, + serialized_end=1446, ) _SETPITCHANDYAWRESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT +_SETPITCHRATEANDYAWRATERESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT _SETMODEREQUEST.fields_by_name['gimbal_mode'].enum_type = _GIMBALMODE _SETMODERESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT _SETROILOCATIONRESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT +_TAKECONTROLREQUEST.fields_by_name['control_mode'].enum_type = _CONTROLMODE +_TAKECONTROLRESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT +_RELEASECONTROLRESPONSE.fields_by_name['gimbal_result'].message_type = _GIMBALRESULT +_CONTROLRESPONSE.fields_by_name['control_status'].message_type = _CONTROLSTATUS +_CONTROLSTATUS.fields_by_name['control_mode'].enum_type = _CONTROLMODE _GIMBALRESULT.fields_by_name['result'].enum_type = _GIMBALRESULT_RESULT _GIMBALRESULT_RESULT.containing_type = _GIMBALRESULT DESCRIPTOR.message_types_by_name['SetPitchAndYawRequest'] = _SETPITCHANDYAWREQUEST DESCRIPTOR.message_types_by_name['SetPitchAndYawResponse'] = _SETPITCHANDYAWRESPONSE +DESCRIPTOR.message_types_by_name['SetPitchRateAndYawRateRequest'] = _SETPITCHRATEANDYAWRATEREQUEST +DESCRIPTOR.message_types_by_name['SetPitchRateAndYawRateResponse'] = _SETPITCHRATEANDYAWRATERESPONSE DESCRIPTOR.message_types_by_name['SetModeRequest'] = _SETMODEREQUEST DESCRIPTOR.message_types_by_name['SetModeResponse'] = _SETMODERESPONSE DESCRIPTOR.message_types_by_name['SetRoiLocationRequest'] = _SETROILOCATIONREQUEST DESCRIPTOR.message_types_by_name['SetRoiLocationResponse'] = _SETROILOCATIONRESPONSE +DESCRIPTOR.message_types_by_name['TakeControlRequest'] = _TAKECONTROLREQUEST +DESCRIPTOR.message_types_by_name['TakeControlResponse'] = _TAKECONTROLRESPONSE +DESCRIPTOR.message_types_by_name['ReleaseControlRequest'] = _RELEASECONTROLREQUEST +DESCRIPTOR.message_types_by_name['ReleaseControlResponse'] = _RELEASECONTROLRESPONSE +DESCRIPTOR.message_types_by_name['SubscribeControlRequest'] = _SUBSCRIBECONTROLREQUEST +DESCRIPTOR.message_types_by_name['ControlResponse'] = _CONTROLRESPONSE +DESCRIPTOR.message_types_by_name['ControlStatus'] = _CONTROLSTATUS DESCRIPTOR.message_types_by_name['GimbalResult'] = _GIMBALRESULT DESCRIPTOR.enum_types_by_name['GimbalMode'] = _GIMBALMODE +DESCRIPTOR.enum_types_by_name['ControlMode'] = _CONTROLMODE _sym_db.RegisterFileDescriptor(DESCRIPTOR) SetPitchAndYawRequest = _reflection.GeneratedProtocolMessageType('SetPitchAndYawRequest', (_message.Message,), { @@ -376,6 +735,20 @@ }) _sym_db.RegisterMessage(SetPitchAndYawResponse) +SetPitchRateAndYawRateRequest = _reflection.GeneratedProtocolMessageType('SetPitchRateAndYawRateRequest', (_message.Message,), { + 'DESCRIPTOR' : _SETPITCHRATEANDYAWRATEREQUEST, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetPitchRateAndYawRateRequest) + }) +_sym_db.RegisterMessage(SetPitchRateAndYawRateRequest) + +SetPitchRateAndYawRateResponse = _reflection.GeneratedProtocolMessageType('SetPitchRateAndYawRateResponse', (_message.Message,), { + 'DESCRIPTOR' : _SETPITCHRATEANDYAWRATERESPONSE, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetPitchRateAndYawRateResponse) + }) +_sym_db.RegisterMessage(SetPitchRateAndYawRateResponse) + SetModeRequest = _reflection.GeneratedProtocolMessageType('SetModeRequest', (_message.Message,), { 'DESCRIPTOR' : _SETMODEREQUEST, '__module__' : 'gimbal.gimbal_pb2' @@ -404,6 +777,55 @@ }) _sym_db.RegisterMessage(SetRoiLocationResponse) +TakeControlRequest = _reflection.GeneratedProtocolMessageType('TakeControlRequest', (_message.Message,), { + 'DESCRIPTOR' : _TAKECONTROLREQUEST, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.TakeControlRequest) + }) +_sym_db.RegisterMessage(TakeControlRequest) + +TakeControlResponse = _reflection.GeneratedProtocolMessageType('TakeControlResponse', (_message.Message,), { + 'DESCRIPTOR' : _TAKECONTROLRESPONSE, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.TakeControlResponse) + }) +_sym_db.RegisterMessage(TakeControlResponse) + +ReleaseControlRequest = _reflection.GeneratedProtocolMessageType('ReleaseControlRequest', (_message.Message,), { + 'DESCRIPTOR' : _RELEASECONTROLREQUEST, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ReleaseControlRequest) + }) +_sym_db.RegisterMessage(ReleaseControlRequest) + +ReleaseControlResponse = _reflection.GeneratedProtocolMessageType('ReleaseControlResponse', (_message.Message,), { + 'DESCRIPTOR' : _RELEASECONTROLRESPONSE, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ReleaseControlResponse) + }) +_sym_db.RegisterMessage(ReleaseControlResponse) + +SubscribeControlRequest = _reflection.GeneratedProtocolMessageType('SubscribeControlRequest', (_message.Message,), { + 'DESCRIPTOR' : _SUBSCRIBECONTROLREQUEST, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SubscribeControlRequest) + }) +_sym_db.RegisterMessage(SubscribeControlRequest) + +ControlResponse = _reflection.GeneratedProtocolMessageType('ControlResponse', (_message.Message,), { + 'DESCRIPTOR' : _CONTROLRESPONSE, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlResponse) + }) +_sym_db.RegisterMessage(ControlResponse) + +ControlStatus = _reflection.GeneratedProtocolMessageType('ControlStatus', (_message.Message,), { + 'DESCRIPTOR' : _CONTROLSTATUS, + '__module__' : 'gimbal.gimbal_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlStatus) + }) +_sym_db.RegisterMessage(ControlStatus) + GimbalResult = _reflection.GeneratedProtocolMessageType('GimbalResult', (_message.Message,), { 'DESCRIPTOR' : _GIMBALRESULT, '__module__' : 'gimbal.gimbal_pb2' @@ -421,8 +843,8 @@ index=0, serialized_options=None, create_key=_descriptor._internal_create_key, - serialized_start=776, - serialized_end=1085, + serialized_start=1609, + serialized_end=2352, methods=[ _descriptor.MethodDescriptor( name='SetPitchAndYaw', @@ -434,10 +856,20 @@ serialized_options=None, create_key=_descriptor._internal_create_key, ), + _descriptor.MethodDescriptor( + name='SetPitchRateAndYawRate', + full_name='mavsdk.rpc.gimbal.GimbalService.SetPitchRateAndYawRate', + index=1, + containing_service=None, + input_type=_SETPITCHRATEANDYAWRATEREQUEST, + output_type=_SETPITCHRATEANDYAWRATERESPONSE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), _descriptor.MethodDescriptor( name='SetMode', full_name='mavsdk.rpc.gimbal.GimbalService.SetMode', - index=1, + index=2, containing_service=None, input_type=_SETMODEREQUEST, output_type=_SETMODERESPONSE, @@ -447,13 +879,43 @@ _descriptor.MethodDescriptor( name='SetRoiLocation', full_name='mavsdk.rpc.gimbal.GimbalService.SetRoiLocation', - index=2, + index=3, containing_service=None, input_type=_SETROILOCATIONREQUEST, output_type=_SETROILOCATIONRESPONSE, serialized_options=None, create_key=_descriptor._internal_create_key, ), + _descriptor.MethodDescriptor( + name='TakeControl', + full_name='mavsdk.rpc.gimbal.GimbalService.TakeControl', + index=4, + containing_service=None, + input_type=_TAKECONTROLREQUEST, + output_type=_TAKECONTROLRESPONSE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), + _descriptor.MethodDescriptor( + name='ReleaseControl', + full_name='mavsdk.rpc.gimbal.GimbalService.ReleaseControl', + index=5, + containing_service=None, + input_type=_RELEASECONTROLREQUEST, + output_type=_RELEASECONTROLRESPONSE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), + _descriptor.MethodDescriptor( + name='SubscribeControl', + full_name='mavsdk.rpc.gimbal.GimbalService.SubscribeControl', + index=6, + containing_service=None, + input_type=_SUBSCRIBECONTROLREQUEST, + output_type=_CONTROLRESPONSE, + serialized_options=None, + create_key=_descriptor._internal_create_key, + ), ]) _sym_db.RegisterServiceDescriptor(_GIMBALSERVICE) diff --git a/mavsdk/gimbal_pb2_grpc.py b/mavsdk/gimbal_pb2_grpc.py index 4c1285b1..fdeadc26 100644 --- a/mavsdk/gimbal_pb2_grpc.py +++ b/mavsdk/gimbal_pb2_grpc.py @@ -20,6 +20,11 @@ def __init__(self, channel): request_serializer=gimbal_dot_gimbal__pb2.SetPitchAndYawRequest.SerializeToString, response_deserializer=gimbal_dot_gimbal__pb2.SetPitchAndYawResponse.FromString, ) + self.SetPitchRateAndYawRate = channel.unary_unary( + '/mavsdk.rpc.gimbal.GimbalService/SetPitchRateAndYawRate', + request_serializer=gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateResponse.FromString, + ) self.SetMode = channel.unary_unary( '/mavsdk.rpc.gimbal.GimbalService/SetMode', request_serializer=gimbal_dot_gimbal__pb2.SetModeRequest.SerializeToString, @@ -30,6 +35,21 @@ def __init__(self, channel): request_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.SerializeToString, response_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.FromString, ) + self.TakeControl = channel.unary_unary( + '/mavsdk.rpc.gimbal.GimbalService/TakeControl', + request_serializer=gimbal_dot_gimbal__pb2.TakeControlRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.TakeControlResponse.FromString, + ) + self.ReleaseControl = channel.unary_unary( + '/mavsdk.rpc.gimbal.GimbalService/ReleaseControl', + request_serializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.FromString, + ) + self.SubscribeControl = channel.unary_stream( + '/mavsdk.rpc.gimbal.GimbalService/SubscribeControl', + request_serializer=gimbal_dot_gimbal__pb2.SubscribeControlRequest.SerializeToString, + response_deserializer=gimbal_dot_gimbal__pb2.ControlResponse.FromString, + ) class GimbalServiceServicer(object): @@ -49,6 +69,19 @@ def SetPitchAndYaw(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def SetPitchRateAndYawRate(self, request, context): + """ + + Set gimbal angular rates around pitch and yaw axes. + + This sets the desired angular rates around pitch and yaw axes of a gimbal. + Will return when the command is accepted, however, it might + take the gimbal longer to actually reach the angular rate. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def SetMode(self, request, context): """ Set gimbal mode. @@ -75,6 +108,44 @@ def SetRoiLocation(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def TakeControl(self, request, context): + """ + Take control. + + There can be only two components in control of a gimbal at any given time. + One with "primary" control, and one with "secondary" control. The way the + secondary control is implemented is not specified and hence depends on the + vehicle. + + Components are expected to be cooperative, which means that they can + override each other and should therefore do it carefully. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def ReleaseControl(self, request, context): + """ + Release control. + + Release control, such that other components can control the gimbal. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def SubscribeControl(self, request, context): + """ + Subscribe to control status updates. + + This allows a component to know if it has primary, secondary or + no control over the gimbal. Also, it gives the system and component ids + of the other components in control (if any). + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def add_GimbalServiceServicer_to_server(servicer, server): rpc_method_handlers = { @@ -83,6 +154,11 @@ def add_GimbalServiceServicer_to_server(servicer, server): request_deserializer=gimbal_dot_gimbal__pb2.SetPitchAndYawRequest.FromString, response_serializer=gimbal_dot_gimbal__pb2.SetPitchAndYawResponse.SerializeToString, ), + 'SetPitchRateAndYawRate': grpc.unary_unary_rpc_method_handler( + servicer.SetPitchRateAndYawRate, + request_deserializer=gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateResponse.SerializeToString, + ), 'SetMode': grpc.unary_unary_rpc_method_handler( servicer.SetMode, request_deserializer=gimbal_dot_gimbal__pb2.SetModeRequest.FromString, @@ -93,6 +169,21 @@ def add_GimbalServiceServicer_to_server(servicer, server): request_deserializer=gimbal_dot_gimbal__pb2.SetRoiLocationRequest.FromString, response_serializer=gimbal_dot_gimbal__pb2.SetRoiLocationResponse.SerializeToString, ), + 'TakeControl': grpc.unary_unary_rpc_method_handler( + servicer.TakeControl, + request_deserializer=gimbal_dot_gimbal__pb2.TakeControlRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.TakeControlResponse.SerializeToString, + ), + 'ReleaseControl': grpc.unary_unary_rpc_method_handler( + servicer.ReleaseControl, + request_deserializer=gimbal_dot_gimbal__pb2.ReleaseControlRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.ReleaseControlResponse.SerializeToString, + ), + 'SubscribeControl': grpc.unary_stream_rpc_method_handler( + servicer.SubscribeControl, + request_deserializer=gimbal_dot_gimbal__pb2.SubscribeControlRequest.FromString, + response_serializer=gimbal_dot_gimbal__pb2.ControlResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( 'mavsdk.rpc.gimbal.GimbalService', rpc_method_handlers) @@ -121,6 +212,23 @@ def SetPitchAndYaw(request, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod + def SetPitchRateAndYawRate(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.gimbal.GimbalService/SetPitchRateAndYawRate', + gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateRequest.SerializeToString, + gimbal_dot_gimbal__pb2.SetPitchRateAndYawRateResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + @staticmethod def SetMode(request, target, @@ -154,3 +262,54 @@ def SetRoiLocation(request, gimbal_dot_gimbal__pb2.SetRoiLocationResponse.FromString, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def TakeControl(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.gimbal.GimbalService/TakeControl', + gimbal_dot_gimbal__pb2.TakeControlRequest.SerializeToString, + gimbal_dot_gimbal__pb2.TakeControlResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def ReleaseControl(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.gimbal.GimbalService/ReleaseControl', + gimbal_dot_gimbal__pb2.ReleaseControlRequest.SerializeToString, + gimbal_dot_gimbal__pb2.ReleaseControlResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def SubscribeControl(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_stream(request, target, '/mavsdk.rpc.gimbal.GimbalService/SubscribeControl', + gimbal_dot_gimbal__pb2.SubscribeControlRequest.SerializeToString, + gimbal_dot_gimbal__pb2.ControlResponse.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/mavsdk/telemetry.py b/mavsdk/telemetry.py index ebde1928..e76c0120 100644 --- a/mavsdk/telemetry.py +++ b/mavsdk/telemetry.py @@ -500,6 +500,9 @@ class Quaternion: z : float Quaternion entry 3, also denoted as d + timestamp_us : uint64_t + Timestamp in microseconds + """ @@ -509,12 +512,14 @@ def __init__( w, x, y, - z): + z, + timestamp_us): """ Initializes the Quaternion object """ self.w = w self.x = x self.y = y self.z = z + self.timestamp_us = timestamp_us def __equals__(self, to_compare): """ Checks if two Quaternion are the same """ @@ -525,7 +530,8 @@ def __equals__(self, to_compare): (self.w == to_compare.w) and \ (self.x == to_compare.x) and \ (self.y == to_compare.y) and \ - (self.z == to_compare.z) + (self.z == to_compare.z) and \ + (self.timestamp_us == to_compare.timestamp_us) except AttributeError: return False @@ -536,7 +542,8 @@ def __str__(self): "w: " + str(self.w), "x: " + str(self.x), "y: " + str(self.y), - "z: " + str(self.z) + "z: " + str(self.z), + "timestamp_us: " + str(self.timestamp_us) ]) return f"Quaternion: [{struct_repr}]" @@ -555,7 +562,10 @@ def translate_from_rpc(rpcQuaternion): rpcQuaternion.y, - rpcQuaternion.z + rpcQuaternion.z, + + + rpcQuaternion.timestamp_us ) def translate_to_rpc(self, rpcQuaternion): @@ -586,6 +596,12 @@ def translate_to_rpc(self, rpcQuaternion): + + + rpcQuaternion.timestamp_us = self.timestamp_us + + + class EulerAngle: @@ -608,6 +624,9 @@ class EulerAngle: yaw_deg : float Yaw angle in degrees, positive is clock-wise seen from above + timestamp_us : uint64_t + Timestamp in microseconds + """ @@ -616,11 +635,13 @@ def __init__( self, roll_deg, pitch_deg, - yaw_deg): + yaw_deg, + timestamp_us): """ Initializes the EulerAngle object """ self.roll_deg = roll_deg self.pitch_deg = pitch_deg self.yaw_deg = yaw_deg + self.timestamp_us = timestamp_us def __equals__(self, to_compare): """ Checks if two EulerAngle are the same """ @@ -630,7 +651,8 @@ def __equals__(self, to_compare): return \ (self.roll_deg == to_compare.roll_deg) and \ (self.pitch_deg == to_compare.pitch_deg) and \ - (self.yaw_deg == to_compare.yaw_deg) + (self.yaw_deg == to_compare.yaw_deg) and \ + (self.timestamp_us == to_compare.timestamp_us) except AttributeError: return False @@ -640,7 +662,8 @@ def __str__(self): struct_repr = ", ".join([ "roll_deg: " + str(self.roll_deg), "pitch_deg: " + str(self.pitch_deg), - "yaw_deg: " + str(self.yaw_deg) + "yaw_deg: " + str(self.yaw_deg), + "timestamp_us: " + str(self.timestamp_us) ]) return f"EulerAngle: [{struct_repr}]" @@ -656,7 +679,10 @@ def translate_from_rpc(rpcEulerAngle): rpcEulerAngle.pitch_deg, - rpcEulerAngle.yaw_deg + rpcEulerAngle.yaw_deg, + + + rpcEulerAngle.timestamp_us ) def translate_to_rpc(self, rpcEulerAngle): @@ -681,6 +707,12 @@ def translate_to_rpc(self, rpcEulerAngle): + + + rpcEulerAngle.timestamp_us = self.timestamp_us + + + class AngularVelocityBody: diff --git a/mavsdk/telemetry_pb2.py b/mavsdk/telemetry_pb2.py index 57bf3939..1a25dd92 100644 --- a/mavsdk/telemetry_pb2.py +++ b/mavsdk/telemetry_pb2.py @@ -21,7 +21,7 @@ syntax='proto3', serialized_options=b'\n\023io.mavsdk.telemetryB\016TelemetryProto', create_key=_descriptor._internal_create_key, - serialized_pb=b'\n\x19telemetry/telemetry.proto\x12\x14mavsdk.rpc.telemetry\x1a\x14mavsdk_options.proto\"\x1a\n\x18SubscribePositionRequest\"D\n\x10PositionResponse\x12\x30\n\x08position\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x16\n\x14SubscribeHomeRequest\"<\n\x0cHomeResponse\x12,\n\x04home\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x17\n\x15SubscribeInAirRequest\"\"\n\rInAirResponse\x12\x11\n\tis_in_air\x18\x01 \x01(\x08\"\x1d\n\x1bSubscribeLandedStateRequest\"N\n\x13LandedStateResponse\x12\x37\n\x0clanded_state\x18\x01 \x01(\x0e\x32!.mavsdk.rpc.telemetry.LandedState\"\x17\n\x15SubscribeArmedRequest\"!\n\rArmedResponse\x12\x10\n\x08is_armed\x18\x01 \x01(\x08\"$\n\"SubscribeAttitudeQuaternionRequest\"[\n\x1a\x41ttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\"\x1f\n\x1dSubscribeAttitudeEulerRequest\"Q\n\x15\x41ttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"-\n+SubscribeAttitudeAngularVelocityBodyRequest\"x\n#AttitudeAngularVelocityBodyResponse\x12Q\n\x1e\x61ttitude_angular_velocity_body\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\"*\n(SubscribeCameraAttitudeQuaternionRequest\"a\n CameraAttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\"%\n#SubscribeCameraAttitudeEulerRequest\"W\n\x1b\x43\x61meraAttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"\x1d\n\x1bSubscribeVelocityNedRequest\"N\n\x13VelocityNedResponse\x12\x37\n\x0cvelocity_ned\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"\x19\n\x17SubscribeGpsInfoRequest\"B\n\x0fGpsInfoResponse\x12/\n\x08gps_info\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.GpsInfo\"\x19\n\x17SubscribeBatteryRequest\"A\n\x0f\x42\x61tteryResponse\x12.\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Battery\"\x1c\n\x1aSubscribeFlightModeRequest\"K\n\x12\x46lightModeResponse\x12\x35\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.telemetry.FlightMode\"\x18\n\x16SubscribeHealthRequest\">\n\x0eHealthResponse\x12,\n\x06health\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.Health\"\x1a\n\x18SubscribeRcStatusRequest\"E\n\x10RcStatusResponse\x12\x31\n\trc_status\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.RcStatus\"\x1c\n\x1aSubscribeStatusTextRequest\"K\n\x12StatusTextResponse\x12\x35\n\x0bstatus_text\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.StatusText\"\'\n%SubscribeActuatorControlTargetRequest\"m\n\x1d\x41\x63tuatorControlTargetResponse\x12L\n\x17\x61\x63tuator_control_target\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry.ActuatorControlTarget\"&\n$SubscribeActuatorOutputStatusRequest\"j\n\x1c\x41\x63tuatorOutputStatusResponse\x12J\n\x16\x61\x63tuator_output_status\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.telemetry.ActuatorOutputStatus\"\x1a\n\x18SubscribeOdometryRequest\"D\n\x10OdometryResponse\x12\x30\n\x08odometry\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Odometry\"%\n#SubscribePositionVelocityNedRequest\"g\n\x1bPositionVelocityNedResponse\x12H\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.PositionVelocityNed\"\x1d\n\x1bSubscribeGroundTruthRequest\"N\n\x13GroundTruthResponse\x12\x37\n\x0cground_truth\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.GroundTruth\"\"\n SubscribeFixedwingMetricsRequest\"]\n\x18\x46ixedwingMetricsResponse\x12\x41\n\x11\x66ixedwing_metrics\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.telemetry.FixedwingMetrics\"\x15\n\x13SubscribeImuRequest\"5\n\x0bImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu\"\x1d\n\x1bSubscribeHealthAllOkRequest\"/\n\x13HealthAllOkResponse\x12\x18\n\x10is_health_all_ok\x18\x01 \x01(\x08\"\x1f\n\x1dSubscribeUnixEpochTimeRequest\"(\n\x15UnixEpochTimeResponse\x12\x0f\n\x07time_us\x18\x01 \x01(\x04\" \n\x1eSubscribeDistanceSensorRequest\"W\n\x16\x44istanceSensorResponse\x12=\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.DistanceSensor\")\n\x16SetRatePositionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRatePositionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"%\n\x12SetRateHomeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"V\n\x13SetRateHomeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"&\n\x13SetRateInAirRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"W\n\x14SetRateInAirResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateLandedStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateLandedStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateAttitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateAttitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"<\n)SetRateAttitudeAngularVelocityBodyRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"m\n*SetRateAttitudeAngularVelocityBodyResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"9\n&SetRateCameraAttitudeQuaternionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"j\n\'SetRateCameraAttitudeQuaternionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"/\n\x1cSetRateCameraAttitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"`\n\x1dSetRateCameraAttitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"(\n\x15SetRateGpsInfoRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateGpsInfoResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"(\n\x15SetRateBatteryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateBatteryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateRcStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateRcStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"6\n#SetRateActuatorControlTargetRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"g\n$SetRateActuatorControlTargetResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"5\n\"SetRateActuatorOutputStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"f\n#SetRateActuatorOutputStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateOdometryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateOdometryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"4\n!SetRatePositionVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"e\n\"SetRatePositionVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateGroundTruthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateGroundTruthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"1\n\x1eSetRateFixedwingMetricsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"b\n\x1fSetRateFixedwingMetricsResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"$\n\x11SetRateImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"U\n\x12SetRateImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\".\n\x1bSetRateUnixEpochTimeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"_\n\x1cSetRateUnixEpochTimeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"/\n\x1cSetRateDistanceSensorRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"`\n\x1dSetRateDistanceSensorResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\x1b\n\x19GetGpsGlobalOriginRequest\"\x9f\x01\n\x1aGetGpsGlobalOriginResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\x12@\n\x11gps_global_origin\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.telemetry.GpsGlobalOrigin\"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\\\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"]\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"Y\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12/\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32\x1d.mavsdk.rpc.telemetry.FixType\"I\n\x07\x42\x61ttery\x12\x1a\n\tvoltage_v\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x11remaining_percent\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xc6\x02\n\x06Health\x12.\n\x1bis_gyrometer_calibration_ok\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x32\n\x1fis_accelerometer_calibration_ok\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x31\n\x1eis_magnetometer_calibration_ok\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12*\n\x17is_level_calibration_ok\x18\x04 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\'\n\x14is_local_position_ok\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x15is_global_position_ok\x18\x06 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x13is_home_position_ok\x18\x07 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\"z\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x05\x82\xb5\x18\x01\x30\"N\n\nStatusText\x12\x32\n\x04type\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.telemetry.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t\"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02\"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02\"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02\";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02\"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02\"\xec\x04\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x39\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12?\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12\x39\n\rposition_body\x18\x04 \x01(\x0b\x32\".mavsdk.rpc.telemetry.PositionBody\x12+\n\x01q\x18\x05 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\x12\x39\n\rvelocity_body\x18\x06 \x01(\x0b\x32\".mavsdk.rpc.telemetry.VelocityBody\x12H\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\x12\x39\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\x12=\n\x13velocity_covariance\x18\t \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12\"\x7f\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\"\x7f\n\x13PositionVelocityNed\x12\x33\n\x08position\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.PositionNed\x12\x33\n\x08velocity\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"x\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xf5\x01\n\x03Imu\x12?\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.AccelerationFrd\x12\x46\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry.AngularVelocityFrd\x12\x42\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32&.mavsdk.rpc.telemetry.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x0fGpsGlobalOrigin\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\naltitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\x89\x02\n\x0fTelemetryResult\x12<\n\x06result\x18\x01 \x01(\x0e\x32,.mavsdk.rpc.telemetry.TelemetryResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa3\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\x86\x03\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r\x12\x19\n\x15\x46LIGHT_MODE_RATTITUDE\x10\x0e*\xf9\x01\n\x0eStatusTextType\x12\x1a\n\x16STATUS_TEXT_TYPE_DEBUG\x10\x00\x12\x19\n\x15STATUS_TEXT_TYPE_INFO\x10\x01\x12\x1b\n\x17STATUS_TEXT_TYPE_NOTICE\x10\x02\x12\x1c\n\x18STATUS_TEXT_TYPE_WARNING\x10\x03\x12\x1a\n\x16STATUS_TEXT_TYPE_ERROR\x10\x04\x12\x1d\n\x19STATUS_TEXT_TYPE_CRITICAL\x10\x05\x12\x1a\n\x16STATUS_TEXT_TYPE_ALERT\x10\x06\x12\x1e\n\x1aSTATUS_TEXT_TYPE_EMERGENCY\x10\x07*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04\x32\xf8-\n\x10TelemetryService\x12o\n\x11SubscribePosition\x12..mavsdk.rpc.telemetry.SubscribePositionRequest\x1a&.mavsdk.rpc.telemetry.PositionResponse\"\x00\x30\x01\x12\x63\n\rSubscribeHome\x12*.mavsdk.rpc.telemetry.SubscribeHomeRequest\x1a\".mavsdk.rpc.telemetry.HomeResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeInAir\x12+.mavsdk.rpc.telemetry.SubscribeInAirRequest\x1a#.mavsdk.rpc.telemetry.InAirResponse\"\x00\x30\x01\x12x\n\x14SubscribeLandedState\x12\x31.mavsdk.rpc.telemetry.SubscribeLandedStateRequest\x1a).mavsdk.rpc.telemetry.LandedStateResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeArmed\x12+.mavsdk.rpc.telemetry.SubscribeArmedRequest\x1a#.mavsdk.rpc.telemetry.ArmedResponse\"\x00\x30\x01\x12\x8d\x01\n\x1bSubscribeAttitudeQuaternion\x12\x38.mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest\x1a\x30.mavsdk.rpc.telemetry.AttitudeQuaternionResponse\"\x00\x30\x01\x12~\n\x16SubscribeAttitudeEuler\x12\x33.mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest\x1a+.mavsdk.rpc.telemetry.AttitudeEulerResponse\"\x00\x30\x01\x12\xa8\x01\n$SubscribeAttitudeAngularVelocityBody\x12\x41.mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest\x1a\x39.mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse\"\x00\x30\x01\x12\x9f\x01\n!SubscribeCameraAttitudeQuaternion\x12>.mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest\x1a\x36.mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse\"\x00\x30\x01\x12\x90\x01\n\x1cSubscribeCameraAttitudeEuler\x12\x39.mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest\x1a\x31.mavsdk.rpc.telemetry.CameraAttitudeEulerResponse\"\x00\x30\x01\x12x\n\x14SubscribeVelocityNed\x12\x31.mavsdk.rpc.telemetry.SubscribeVelocityNedRequest\x1a).mavsdk.rpc.telemetry.VelocityNedResponse\"\x00\x30\x01\x12l\n\x10SubscribeGpsInfo\x12-.mavsdk.rpc.telemetry.SubscribeGpsInfoRequest\x1a%.mavsdk.rpc.telemetry.GpsInfoResponse\"\x00\x30\x01\x12l\n\x10SubscribeBattery\x12-.mavsdk.rpc.telemetry.SubscribeBatteryRequest\x1a%.mavsdk.rpc.telemetry.BatteryResponse\"\x00\x30\x01\x12u\n\x13SubscribeFlightMode\x12\x30.mavsdk.rpc.telemetry.SubscribeFlightModeRequest\x1a(.mavsdk.rpc.telemetry.FlightModeResponse\"\x00\x30\x01\x12i\n\x0fSubscribeHealth\x12,.mavsdk.rpc.telemetry.SubscribeHealthRequest\x1a$.mavsdk.rpc.telemetry.HealthResponse\"\x00\x30\x01\x12o\n\x11SubscribeRcStatus\x12..mavsdk.rpc.telemetry.SubscribeRcStatusRequest\x1a&.mavsdk.rpc.telemetry.RcStatusResponse\"\x00\x30\x01\x12u\n\x13SubscribeStatusText\x12\x30.mavsdk.rpc.telemetry.SubscribeStatusTextRequest\x1a(.mavsdk.rpc.telemetry.StatusTextResponse\"\x00\x30\x01\x12\x96\x01\n\x1eSubscribeActuatorControlTarget\x12;.mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest\x1a\x33.mavsdk.rpc.telemetry.ActuatorControlTargetResponse\"\x00\x30\x01\x12\x93\x01\n\x1dSubscribeActuatorOutputStatus\x12:.mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest\x1a\x32.mavsdk.rpc.telemetry.ActuatorOutputStatusResponse\"\x00\x30\x01\x12o\n\x11SubscribeOdometry\x12..mavsdk.rpc.telemetry.SubscribeOdometryRequest\x1a&.mavsdk.rpc.telemetry.OdometryResponse\"\x00\x30\x01\x12\x90\x01\n\x1cSubscribePositionVelocityNed\x12\x39.mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest\x1a\x31.mavsdk.rpc.telemetry.PositionVelocityNedResponse\"\x00\x30\x01\x12x\n\x14SubscribeGroundTruth\x12\x31.mavsdk.rpc.telemetry.SubscribeGroundTruthRequest\x1a).mavsdk.rpc.telemetry.GroundTruthResponse\"\x00\x30\x01\x12\x87\x01\n\x19SubscribeFixedwingMetrics\x12\x36.mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest\x1a..mavsdk.rpc.telemetry.FixedwingMetricsResponse\"\x00\x30\x01\x12`\n\x0cSubscribeImu\x12).mavsdk.rpc.telemetry.SubscribeImuRequest\x1a!.mavsdk.rpc.telemetry.ImuResponse\"\x00\x30\x01\x12x\n\x14SubscribeHealthAllOk\x12\x31.mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest\x1a).mavsdk.rpc.telemetry.HealthAllOkResponse\"\x00\x30\x01\x12~\n\x16SubscribeUnixEpochTime\x12\x33.mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest\x1a+.mavsdk.rpc.telemetry.UnixEpochTimeResponse\"\x00\x30\x01\x12\x81\x01\n\x17SubscribeDistanceSensor\x12\x34.mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest\x1a,.mavsdk.rpc.telemetry.DistanceSensorResponse\"\x00\x30\x01\x12p\n\x0fSetRatePosition\x12,.mavsdk.rpc.telemetry.SetRatePositionRequest\x1a-.mavsdk.rpc.telemetry.SetRatePositionResponse\"\x00\x12\x64\n\x0bSetRateHome\x12(.mavsdk.rpc.telemetry.SetRateHomeRequest\x1a).mavsdk.rpc.telemetry.SetRateHomeResponse\"\x00\x12g\n\x0cSetRateInAir\x12).mavsdk.rpc.telemetry.SetRateInAirRequest\x1a*.mavsdk.rpc.telemetry.SetRateInAirResponse\"\x00\x12y\n\x12SetRateLandedState\x12/.mavsdk.rpc.telemetry.SetRateLandedStateRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateLandedStateResponse\"\x00\x12p\n\x0fSetRateAttitude\x12,.mavsdk.rpc.telemetry.SetRateAttitudeRequest\x1a-.mavsdk.rpc.telemetry.SetRateAttitudeResponse\"\x00\x12\x82\x01\n\x15SetRateCameraAttitude\x12\x32.mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse\"\x00\x12y\n\x12SetRateVelocityNed\x12/.mavsdk.rpc.telemetry.SetRateVelocityNedRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateVelocityNedResponse\"\x00\x12m\n\x0eSetRateGpsInfo\x12+.mavsdk.rpc.telemetry.SetRateGpsInfoRequest\x1a,.mavsdk.rpc.telemetry.SetRateGpsInfoResponse\"\x00\x12m\n\x0eSetRateBattery\x12+.mavsdk.rpc.telemetry.SetRateBatteryRequest\x1a,.mavsdk.rpc.telemetry.SetRateBatteryResponse\"\x00\x12p\n\x0fSetRateRcStatus\x12,.mavsdk.rpc.telemetry.SetRateRcStatusRequest\x1a-.mavsdk.rpc.telemetry.SetRateRcStatusResponse\"\x00\x12\x97\x01\n\x1cSetRateActuatorControlTarget\x12\x39.mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest\x1a:.mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse\"\x00\x12\x94\x01\n\x1bSetRateActuatorOutputStatus\x12\x38.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest\x1a\x39.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse\"\x00\x12p\n\x0fSetRateOdometry\x12,.mavsdk.rpc.telemetry.SetRateOdometryRequest\x1a-.mavsdk.rpc.telemetry.SetRateOdometryResponse\"\x00\x12\x91\x01\n\x1aSetRatePositionVelocityNed\x12\x37.mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest\x1a\x38.mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse\"\x00\x12y\n\x12SetRateGroundTruth\x12/.mavsdk.rpc.telemetry.SetRateGroundTruthRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateGroundTruthResponse\"\x00\x12\x88\x01\n\x17SetRateFixedwingMetrics\x12\x34.mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest\x1a\x35.mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse\"\x00\x12\x61\n\nSetRateImu\x12\'.mavsdk.rpc.telemetry.SetRateImuRequest\x1a(.mavsdk.rpc.telemetry.SetRateImuResponse\"\x00\x12\x7f\n\x14SetRateUnixEpochTime\x12\x31.mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse\"\x00\x12\x82\x01\n\x15SetRateDistanceSensor\x12\x32.mavsdk.rpc.telemetry.SetRateDistanceSensorRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateDistanceSensorResponse\"\x00\x12y\n\x12GetGpsGlobalOrigin\x12/.mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest\x1a\x30.mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse\"\x00\x42%\n\x13io.mavsdk.telemetryB\x0eTelemetryProtob\x06proto3' + serialized_pb=b'\n\x19telemetry/telemetry.proto\x12\x14mavsdk.rpc.telemetry\x1a\x14mavsdk_options.proto\"\x1a\n\x18SubscribePositionRequest\"D\n\x10PositionResponse\x12\x30\n\x08position\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x16\n\x14SubscribeHomeRequest\"<\n\x0cHomeResponse\x12,\n\x04home\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Position\"\x17\n\x15SubscribeInAirRequest\"\"\n\rInAirResponse\x12\x11\n\tis_in_air\x18\x01 \x01(\x08\"\x1d\n\x1bSubscribeLandedStateRequest\"N\n\x13LandedStateResponse\x12\x37\n\x0clanded_state\x18\x01 \x01(\x0e\x32!.mavsdk.rpc.telemetry.LandedState\"\x17\n\x15SubscribeArmedRequest\"!\n\rArmedResponse\x12\x10\n\x08is_armed\x18\x01 \x01(\x08\"$\n\"SubscribeAttitudeQuaternionRequest\"[\n\x1a\x41ttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\"\x1f\n\x1dSubscribeAttitudeEulerRequest\"Q\n\x15\x41ttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"-\n+SubscribeAttitudeAngularVelocityBodyRequest\"x\n#AttitudeAngularVelocityBodyResponse\x12Q\n\x1e\x61ttitude_angular_velocity_body\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\"*\n(SubscribeCameraAttitudeQuaternionRequest\"a\n CameraAttitudeQuaternionResponse\x12=\n\x13\x61ttitude_quaternion\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\"%\n#SubscribeCameraAttitudeEulerRequest\"W\n\x1b\x43\x61meraAttitudeEulerResponse\x12\x38\n\x0e\x61ttitude_euler\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.EulerAngle\"\x1d\n\x1bSubscribeVelocityNedRequest\"N\n\x13VelocityNedResponse\x12\x37\n\x0cvelocity_ned\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"\x19\n\x17SubscribeGpsInfoRequest\"B\n\x0fGpsInfoResponse\x12/\n\x08gps_info\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.GpsInfo\"\x19\n\x17SubscribeBatteryRequest\"A\n\x0f\x42\x61tteryResponse\x12.\n\x07\x62\x61ttery\x18\x01 \x01(\x0b\x32\x1d.mavsdk.rpc.telemetry.Battery\"\x1c\n\x1aSubscribeFlightModeRequest\"K\n\x12\x46lightModeResponse\x12\x35\n\x0b\x66light_mode\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.telemetry.FlightMode\"\x18\n\x16SubscribeHealthRequest\">\n\x0eHealthResponse\x12,\n\x06health\x18\x01 \x01(\x0b\x32\x1c.mavsdk.rpc.telemetry.Health\"\x1a\n\x18SubscribeRcStatusRequest\"E\n\x10RcStatusResponse\x12\x31\n\trc_status\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.RcStatus\"\x1c\n\x1aSubscribeStatusTextRequest\"K\n\x12StatusTextResponse\x12\x35\n\x0bstatus_text\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.telemetry.StatusText\"\'\n%SubscribeActuatorControlTargetRequest\"m\n\x1d\x41\x63tuatorControlTargetResponse\x12L\n\x17\x61\x63tuator_control_target\x18\x01 \x01(\x0b\x32+.mavsdk.rpc.telemetry.ActuatorControlTarget\"&\n$SubscribeActuatorOutputStatusRequest\"j\n\x1c\x41\x63tuatorOutputStatusResponse\x12J\n\x16\x61\x63tuator_output_status\x18\x01 \x01(\x0b\x32*.mavsdk.rpc.telemetry.ActuatorOutputStatus\"\x1a\n\x18SubscribeOdometryRequest\"D\n\x10OdometryResponse\x12\x30\n\x08odometry\x18\x01 \x01(\x0b\x32\x1e.mavsdk.rpc.telemetry.Odometry\"%\n#SubscribePositionVelocityNedRequest\"g\n\x1bPositionVelocityNedResponse\x12H\n\x15position_velocity_ned\x18\x01 \x01(\x0b\x32).mavsdk.rpc.telemetry.PositionVelocityNed\"\x1d\n\x1bSubscribeGroundTruthRequest\"N\n\x13GroundTruthResponse\x12\x37\n\x0cground_truth\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.GroundTruth\"\"\n SubscribeFixedwingMetricsRequest\"]\n\x18\x46ixedwingMetricsResponse\x12\x41\n\x11\x66ixedwing_metrics\x18\x01 \x01(\x0b\x32&.mavsdk.rpc.telemetry.FixedwingMetrics\"\x15\n\x13SubscribeImuRequest\"5\n\x0bImuResponse\x12&\n\x03imu\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.telemetry.Imu\"\x1d\n\x1bSubscribeHealthAllOkRequest\"/\n\x13HealthAllOkResponse\x12\x18\n\x10is_health_all_ok\x18\x01 \x01(\x08\"\x1f\n\x1dSubscribeUnixEpochTimeRequest\"(\n\x15UnixEpochTimeResponse\x12\x0f\n\x07time_us\x18\x01 \x01(\x04\" \n\x1eSubscribeDistanceSensorRequest\"W\n\x16\x44istanceSensorResponse\x12=\n\x0f\x64istance_sensor\x18\x01 \x01(\x0b\x32$.mavsdk.rpc.telemetry.DistanceSensor\")\n\x16SetRatePositionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRatePositionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"%\n\x12SetRateHomeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"V\n\x13SetRateHomeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"&\n\x13SetRateInAirRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"W\n\x14SetRateInAirResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateLandedStateRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateLandedStateResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateAttitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateAttitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"<\n)SetRateAttitudeAngularVelocityBodyRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"m\n*SetRateAttitudeAngularVelocityBodyResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"9\n&SetRateCameraAttitudeQuaternionRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"j\n\'SetRateCameraAttitudeQuaternionResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"/\n\x1cSetRateCameraAttitudeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"`\n\x1dSetRateCameraAttitudeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"(\n\x15SetRateGpsInfoRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateGpsInfoResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"(\n\x15SetRateBatteryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Y\n\x16SetRateBatteryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateRcStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateRcStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"6\n#SetRateActuatorControlTargetRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"g\n$SetRateActuatorControlTargetResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"5\n\"SetRateActuatorOutputStatusRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"f\n#SetRateActuatorOutputStatusResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\")\n\x16SetRateOdometryRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"Z\n\x17SetRateOdometryResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"4\n!SetRatePositionVelocityNedRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"e\n\"SetRatePositionVelocityNedResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\",\n\x19SetRateGroundTruthRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"]\n\x1aSetRateGroundTruthResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"1\n\x1eSetRateFixedwingMetricsRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"b\n\x1fSetRateFixedwingMetricsResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"$\n\x11SetRateImuRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"U\n\x12SetRateImuResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\".\n\x1bSetRateUnixEpochTimeRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"_\n\x1cSetRateUnixEpochTimeResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"/\n\x1cSetRateDistanceSensorRequest\x12\x0f\n\x07rate_hz\x18\x01 \x01(\x01\"`\n\x1dSetRateDistanceSensorResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\"\x1b\n\x19GetGpsGlobalOriginRequest\"\x9f\x01\n\x1aGetGpsGlobalOriginResponse\x12?\n\x10telemetry_result\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.TelemetryResult\x12@\n\x11gps_global_origin\x18\x02 \x01(\x0b\x32%.mavsdk.rpc.telemetry.GpsGlobalOrigin\"\x95\x01\n\x08Position\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13relative_altitude_m\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"r\n\nQuaternion\x12\x12\n\x01w\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01x\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01y\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x12\n\x01z\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x05 \x01(\x04\"s\n\nEulerAngle\x12\x19\n\x08roll_deg\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tpitch_deg\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x18\n\x07yaw_deg\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x14\n\x0ctimestamp_us\x18\x04 \x01(\x04\"l\n\x13\x41ngularVelocityBody\x12\x1b\n\nroll_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bpitch_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tyaw_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"Y\n\x07GpsInfo\x12\x1d\n\x0enum_satellites\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12/\n\x08\x66ix_type\x18\x02 \x01(\x0e\x32\x1d.mavsdk.rpc.telemetry.FixType\"I\n\x07\x42\x61ttery\x12\x1a\n\tvoltage_v\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\"\n\x11remaining_percent\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xc6\x02\n\x06Health\x12.\n\x1bis_gyrometer_calibration_ok\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x32\n\x1fis_accelerometer_calibration_ok\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x31\n\x1eis_magnetometer_calibration_ok\x18\x03 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12*\n\x17is_level_calibration_ok\x18\x04 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\'\n\x14is_local_position_ok\x18\x05 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12(\n\x15is_global_position_ok\x18\x06 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x13is_home_position_ok\x18\x07 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\"z\n\x08RcStatus\x12%\n\x12was_available_once\x18\x01 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12\x1f\n\x0cis_available\x18\x02 \x01(\x08\x42\t\x82\xb5\x18\x05\x66\x61lse\x12&\n\x17signal_strength_percent\x18\x03 \x01(\x02\x42\x05\x82\xb5\x18\x01\x30\"N\n\nStatusText\x12\x32\n\x04type\x18\x01 \x01(\x0e\x32$.mavsdk.rpc.telemetry.StatusTextType\x12\x0c\n\x04text\x18\x02 \x01(\t\"?\n\x15\x41\x63tuatorControlTarget\x12\x14\n\x05group\x18\x01 \x01(\x05\x42\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x63ontrols\x18\x02 \x03(\x02\"?\n\x14\x41\x63tuatorOutputStatus\x12\x15\n\x06\x61\x63tive\x18\x01 \x01(\rB\x05\x82\xb5\x18\x01\x30\x12\x10\n\x08\x61\x63tuator\x18\x02 \x03(\x02\"\'\n\nCovariance\x12\x19\n\x11\x63ovariance_matrix\x18\x01 \x03(\x02\";\n\x0cVelocityBody\x12\r\n\x05x_m_s\x18\x01 \x01(\x02\x12\r\n\x05y_m_s\x18\x02 \x01(\x02\x12\r\n\x05z_m_s\x18\x03 \x01(\x02\"5\n\x0cPositionBody\x12\x0b\n\x03x_m\x18\x01 \x01(\x02\x12\x0b\n\x03y_m\x18\x02 \x01(\x02\x12\x0b\n\x03z_m\x18\x03 \x01(\x02\"\xec\x04\n\x08Odometry\x12\x11\n\ttime_usec\x18\x01 \x01(\x04\x12\x39\n\x08\x66rame_id\x18\x02 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12?\n\x0e\x63hild_frame_id\x18\x03 \x01(\x0e\x32\'.mavsdk.rpc.telemetry.Odometry.MavFrame\x12\x39\n\rposition_body\x18\x04 \x01(\x0b\x32\".mavsdk.rpc.telemetry.PositionBody\x12+\n\x01q\x18\x05 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Quaternion\x12\x39\n\rvelocity_body\x18\x06 \x01(\x0b\x32\".mavsdk.rpc.telemetry.VelocityBody\x12H\n\x15\x61ngular_velocity_body\x18\x07 \x01(\x0b\x32).mavsdk.rpc.telemetry.AngularVelocityBody\x12\x39\n\x0fpose_covariance\x18\x08 \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\x12=\n\x13velocity_covariance\x18\t \x01(\x0b\x32 .mavsdk.rpc.telemetry.Covariance\"j\n\x08MavFrame\x12\x13\n\x0fMAV_FRAME_UNDEF\x10\x00\x12\x16\n\x12MAV_FRAME_BODY_NED\x10\x08\x12\x18\n\x14MAV_FRAME_VISION_NED\x10\x10\x12\x17\n\x13MAV_FRAME_ESTIM_NED\x10\x12\"\x7f\n\x0e\x44istanceSensor\x12#\n\x12minimum_distance_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12maximum_distance_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12#\n\x12\x63urrent_distance_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"Y\n\x0bPositionNed\x12\x18\n\x07north_m\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x65\x61st_m\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x17\n\x06\x64own_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"D\n\x0bVelocityNed\x12\x11\n\tnorth_m_s\x18\x01 \x01(\x02\x12\x10\n\x08\x65\x61st_m_s\x18\x02 \x01(\x02\x12\x10\n\x08\x64own_m_s\x18\x03 \x01(\x02\"\x7f\n\x13PositionVelocityNed\x12\x33\n\x08position\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.telemetry.PositionNed\x12\x33\n\x08velocity\x18\x02 \x01(\x0b\x32!.mavsdk.rpc.telemetry.VelocityNed\"r\n\x0bGroundTruth\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13\x61\x62solute_altitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"x\n\x10\x46ixedwingMetrics\x12\x1d\n\x0c\x61irspeed_m_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12$\n\x13throttle_percentage\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1f\n\x0e\x63limb_rate_m_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"i\n\x0f\x41\x63\x63\x65lerationFrd\x12\x1d\n\x0c\x66orward_m_s2\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\nright_m_s2\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1a\n\tdown_m_s2\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"o\n\x12\x41ngularVelocityFrd\x12\x1e\n\rforward_rad_s\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_rad_s\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_rad_s\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x10MagneticFieldFrd\x12\x1e\n\rforward_gauss\x18\x01 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1c\n\x0bright_gauss\x18\x02 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\ndown_gauss\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\xf5\x01\n\x03Imu\x12?\n\x10\x61\x63\x63\x65leration_frd\x18\x01 \x01(\x0b\x32%.mavsdk.rpc.telemetry.AccelerationFrd\x12\x46\n\x14\x61ngular_velocity_frd\x18\x02 \x01(\x0b\x32(.mavsdk.rpc.telemetry.AngularVelocityFrd\x12\x42\n\x12magnetic_field_frd\x18\x03 \x01(\x0b\x32&.mavsdk.rpc.telemetry.MagneticFieldFrd\x12!\n\x10temperature_degc\x18\x04 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"m\n\x0fGpsGlobalOrigin\x12\x1d\n\x0clatitude_deg\x18\x01 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1e\n\rlongitude_deg\x18\x02 \x01(\x01\x42\x07\x82\xb5\x18\x03NaN\x12\x1b\n\naltitude_m\x18\x03 \x01(\x02\x42\x07\x82\xb5\x18\x03NaN\"\x89\x02\n\x0fTelemetryResult\x12<\n\x06result\x18\x01 \x01(\x0e\x32,.mavsdk.rpc.telemetry.TelemetryResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa3\x01\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x14\n\x10RESULT_NO_SYSTEM\x10\x02\x12\x1b\n\x17RESULT_CONNECTION_ERROR\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x19\n\x15RESULT_COMMAND_DENIED\x10\x05\x12\x12\n\x0eRESULT_TIMEOUT\x10\x06*\xa4\x01\n\x07\x46ixType\x12\x13\n\x0f\x46IX_TYPE_NO_GPS\x10\x00\x12\x13\n\x0f\x46IX_TYPE_NO_FIX\x10\x01\x12\x13\n\x0f\x46IX_TYPE_FIX_2D\x10\x02\x12\x13\n\x0f\x46IX_TYPE_FIX_3D\x10\x03\x12\x15\n\x11\x46IX_TYPE_FIX_DGPS\x10\x04\x12\x16\n\x12\x46IX_TYPE_RTK_FLOAT\x10\x05\x12\x16\n\x12\x46IX_TYPE_RTK_FIXED\x10\x06*\x86\x03\n\nFlightMode\x12\x17\n\x13\x46LIGHT_MODE_UNKNOWN\x10\x00\x12\x15\n\x11\x46LIGHT_MODE_READY\x10\x01\x12\x17\n\x13\x46LIGHT_MODE_TAKEOFF\x10\x02\x12\x14\n\x10\x46LIGHT_MODE_HOLD\x10\x03\x12\x17\n\x13\x46LIGHT_MODE_MISSION\x10\x04\x12 \n\x1c\x46LIGHT_MODE_RETURN_TO_LAUNCH\x10\x05\x12\x14\n\x10\x46LIGHT_MODE_LAND\x10\x06\x12\x18\n\x14\x46LIGHT_MODE_OFFBOARD\x10\x07\x12\x19\n\x15\x46LIGHT_MODE_FOLLOW_ME\x10\x08\x12\x16\n\x12\x46LIGHT_MODE_MANUAL\x10\t\x12\x16\n\x12\x46LIGHT_MODE_ALTCTL\x10\n\x12\x16\n\x12\x46LIGHT_MODE_POSCTL\x10\x0b\x12\x14\n\x10\x46LIGHT_MODE_ACRO\x10\x0c\x12\x1a\n\x16\x46LIGHT_MODE_STABILIZED\x10\r\x12\x19\n\x15\x46LIGHT_MODE_RATTITUDE\x10\x0e*\xf9\x01\n\x0eStatusTextType\x12\x1a\n\x16STATUS_TEXT_TYPE_DEBUG\x10\x00\x12\x19\n\x15STATUS_TEXT_TYPE_INFO\x10\x01\x12\x1b\n\x17STATUS_TEXT_TYPE_NOTICE\x10\x02\x12\x1c\n\x18STATUS_TEXT_TYPE_WARNING\x10\x03\x12\x1a\n\x16STATUS_TEXT_TYPE_ERROR\x10\x04\x12\x1d\n\x19STATUS_TEXT_TYPE_CRITICAL\x10\x05\x12\x1a\n\x16STATUS_TEXT_TYPE_ALERT\x10\x06\x12\x1e\n\x1aSTATUS_TEXT_TYPE_EMERGENCY\x10\x07*\x93\x01\n\x0bLandedState\x12\x18\n\x14LANDED_STATE_UNKNOWN\x10\x00\x12\x1a\n\x16LANDED_STATE_ON_GROUND\x10\x01\x12\x17\n\x13LANDED_STATE_IN_AIR\x10\x02\x12\x1b\n\x17LANDED_STATE_TAKING_OFF\x10\x03\x12\x18\n\x14LANDED_STATE_LANDING\x10\x04\x32\xf8-\n\x10TelemetryService\x12o\n\x11SubscribePosition\x12..mavsdk.rpc.telemetry.SubscribePositionRequest\x1a&.mavsdk.rpc.telemetry.PositionResponse\"\x00\x30\x01\x12\x63\n\rSubscribeHome\x12*.mavsdk.rpc.telemetry.SubscribeHomeRequest\x1a\".mavsdk.rpc.telemetry.HomeResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeInAir\x12+.mavsdk.rpc.telemetry.SubscribeInAirRequest\x1a#.mavsdk.rpc.telemetry.InAirResponse\"\x00\x30\x01\x12x\n\x14SubscribeLandedState\x12\x31.mavsdk.rpc.telemetry.SubscribeLandedStateRequest\x1a).mavsdk.rpc.telemetry.LandedStateResponse\"\x00\x30\x01\x12\x66\n\x0eSubscribeArmed\x12+.mavsdk.rpc.telemetry.SubscribeArmedRequest\x1a#.mavsdk.rpc.telemetry.ArmedResponse\"\x00\x30\x01\x12\x8d\x01\n\x1bSubscribeAttitudeQuaternion\x12\x38.mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest\x1a\x30.mavsdk.rpc.telemetry.AttitudeQuaternionResponse\"\x00\x30\x01\x12~\n\x16SubscribeAttitudeEuler\x12\x33.mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest\x1a+.mavsdk.rpc.telemetry.AttitudeEulerResponse\"\x00\x30\x01\x12\xa8\x01\n$SubscribeAttitudeAngularVelocityBody\x12\x41.mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest\x1a\x39.mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse\"\x00\x30\x01\x12\x9f\x01\n!SubscribeCameraAttitudeQuaternion\x12>.mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest\x1a\x36.mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse\"\x00\x30\x01\x12\x90\x01\n\x1cSubscribeCameraAttitudeEuler\x12\x39.mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest\x1a\x31.mavsdk.rpc.telemetry.CameraAttitudeEulerResponse\"\x00\x30\x01\x12x\n\x14SubscribeVelocityNed\x12\x31.mavsdk.rpc.telemetry.SubscribeVelocityNedRequest\x1a).mavsdk.rpc.telemetry.VelocityNedResponse\"\x00\x30\x01\x12l\n\x10SubscribeGpsInfo\x12-.mavsdk.rpc.telemetry.SubscribeGpsInfoRequest\x1a%.mavsdk.rpc.telemetry.GpsInfoResponse\"\x00\x30\x01\x12l\n\x10SubscribeBattery\x12-.mavsdk.rpc.telemetry.SubscribeBatteryRequest\x1a%.mavsdk.rpc.telemetry.BatteryResponse\"\x00\x30\x01\x12u\n\x13SubscribeFlightMode\x12\x30.mavsdk.rpc.telemetry.SubscribeFlightModeRequest\x1a(.mavsdk.rpc.telemetry.FlightModeResponse\"\x00\x30\x01\x12i\n\x0fSubscribeHealth\x12,.mavsdk.rpc.telemetry.SubscribeHealthRequest\x1a$.mavsdk.rpc.telemetry.HealthResponse\"\x00\x30\x01\x12o\n\x11SubscribeRcStatus\x12..mavsdk.rpc.telemetry.SubscribeRcStatusRequest\x1a&.mavsdk.rpc.telemetry.RcStatusResponse\"\x00\x30\x01\x12u\n\x13SubscribeStatusText\x12\x30.mavsdk.rpc.telemetry.SubscribeStatusTextRequest\x1a(.mavsdk.rpc.telemetry.StatusTextResponse\"\x00\x30\x01\x12\x96\x01\n\x1eSubscribeActuatorControlTarget\x12;.mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest\x1a\x33.mavsdk.rpc.telemetry.ActuatorControlTargetResponse\"\x00\x30\x01\x12\x93\x01\n\x1dSubscribeActuatorOutputStatus\x12:.mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest\x1a\x32.mavsdk.rpc.telemetry.ActuatorOutputStatusResponse\"\x00\x30\x01\x12o\n\x11SubscribeOdometry\x12..mavsdk.rpc.telemetry.SubscribeOdometryRequest\x1a&.mavsdk.rpc.telemetry.OdometryResponse\"\x00\x30\x01\x12\x90\x01\n\x1cSubscribePositionVelocityNed\x12\x39.mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest\x1a\x31.mavsdk.rpc.telemetry.PositionVelocityNedResponse\"\x00\x30\x01\x12x\n\x14SubscribeGroundTruth\x12\x31.mavsdk.rpc.telemetry.SubscribeGroundTruthRequest\x1a).mavsdk.rpc.telemetry.GroundTruthResponse\"\x00\x30\x01\x12\x87\x01\n\x19SubscribeFixedwingMetrics\x12\x36.mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest\x1a..mavsdk.rpc.telemetry.FixedwingMetricsResponse\"\x00\x30\x01\x12`\n\x0cSubscribeImu\x12).mavsdk.rpc.telemetry.SubscribeImuRequest\x1a!.mavsdk.rpc.telemetry.ImuResponse\"\x00\x30\x01\x12x\n\x14SubscribeHealthAllOk\x12\x31.mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest\x1a).mavsdk.rpc.telemetry.HealthAllOkResponse\"\x00\x30\x01\x12~\n\x16SubscribeUnixEpochTime\x12\x33.mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest\x1a+.mavsdk.rpc.telemetry.UnixEpochTimeResponse\"\x00\x30\x01\x12\x81\x01\n\x17SubscribeDistanceSensor\x12\x34.mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest\x1a,.mavsdk.rpc.telemetry.DistanceSensorResponse\"\x00\x30\x01\x12p\n\x0fSetRatePosition\x12,.mavsdk.rpc.telemetry.SetRatePositionRequest\x1a-.mavsdk.rpc.telemetry.SetRatePositionResponse\"\x00\x12\x64\n\x0bSetRateHome\x12(.mavsdk.rpc.telemetry.SetRateHomeRequest\x1a).mavsdk.rpc.telemetry.SetRateHomeResponse\"\x00\x12g\n\x0cSetRateInAir\x12).mavsdk.rpc.telemetry.SetRateInAirRequest\x1a*.mavsdk.rpc.telemetry.SetRateInAirResponse\"\x00\x12y\n\x12SetRateLandedState\x12/.mavsdk.rpc.telemetry.SetRateLandedStateRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateLandedStateResponse\"\x00\x12p\n\x0fSetRateAttitude\x12,.mavsdk.rpc.telemetry.SetRateAttitudeRequest\x1a-.mavsdk.rpc.telemetry.SetRateAttitudeResponse\"\x00\x12\x82\x01\n\x15SetRateCameraAttitude\x12\x32.mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse\"\x00\x12y\n\x12SetRateVelocityNed\x12/.mavsdk.rpc.telemetry.SetRateVelocityNedRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateVelocityNedResponse\"\x00\x12m\n\x0eSetRateGpsInfo\x12+.mavsdk.rpc.telemetry.SetRateGpsInfoRequest\x1a,.mavsdk.rpc.telemetry.SetRateGpsInfoResponse\"\x00\x12m\n\x0eSetRateBattery\x12+.mavsdk.rpc.telemetry.SetRateBatteryRequest\x1a,.mavsdk.rpc.telemetry.SetRateBatteryResponse\"\x00\x12p\n\x0fSetRateRcStatus\x12,.mavsdk.rpc.telemetry.SetRateRcStatusRequest\x1a-.mavsdk.rpc.telemetry.SetRateRcStatusResponse\"\x00\x12\x97\x01\n\x1cSetRateActuatorControlTarget\x12\x39.mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest\x1a:.mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse\"\x00\x12\x94\x01\n\x1bSetRateActuatorOutputStatus\x12\x38.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest\x1a\x39.mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse\"\x00\x12p\n\x0fSetRateOdometry\x12,.mavsdk.rpc.telemetry.SetRateOdometryRequest\x1a-.mavsdk.rpc.telemetry.SetRateOdometryResponse\"\x00\x12\x91\x01\n\x1aSetRatePositionVelocityNed\x12\x37.mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest\x1a\x38.mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse\"\x00\x12y\n\x12SetRateGroundTruth\x12/.mavsdk.rpc.telemetry.SetRateGroundTruthRequest\x1a\x30.mavsdk.rpc.telemetry.SetRateGroundTruthResponse\"\x00\x12\x88\x01\n\x17SetRateFixedwingMetrics\x12\x34.mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest\x1a\x35.mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse\"\x00\x12\x61\n\nSetRateImu\x12\'.mavsdk.rpc.telemetry.SetRateImuRequest\x1a(.mavsdk.rpc.telemetry.SetRateImuResponse\"\x00\x12\x7f\n\x14SetRateUnixEpochTime\x12\x31.mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest\x1a\x32.mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse\"\x00\x12\x82\x01\n\x15SetRateDistanceSensor\x12\x32.mavsdk.rpc.telemetry.SetRateDistanceSensorRequest\x1a\x33.mavsdk.rpc.telemetry.SetRateDistanceSensorResponse\"\x00\x12y\n\x12GetGpsGlobalOrigin\x12/.mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest\x1a\x30.mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse\"\x00\x42%\n\x13io.mavsdk.telemetryB\x0eTelemetryProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -70,8 +70,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=9903, - serialized_end=10067, + serialized_start=9947, + serialized_end=10111, ) _sym_db.RegisterEnumDescriptor(_FIXTYPE) @@ -161,8 +161,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=10070, - serialized_end=10460, + serialized_start=10114, + serialized_end=10504, ) _sym_db.RegisterEnumDescriptor(_FLIGHTMODE) @@ -217,8 +217,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=10463, - serialized_end=10712, + serialized_start=10507, + serialized_end=10756, ) _sym_db.RegisterEnumDescriptor(_STATUSTEXTTYPE) @@ -258,8 +258,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=10715, - serialized_end=10862, + serialized_start=10759, + serialized_end=10906, ) _sym_db.RegisterEnumDescriptor(_LANDEDSTATE) @@ -331,8 +331,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=8179, - serialized_end=8285, + serialized_start=8223, + serialized_end=8329, ) _sym_db.RegisterEnumDescriptor(_ODOMETRY_MAVFRAME) @@ -381,8 +381,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=9737, - serialized_end=9900, + serialized_start=9781, + serialized_end=9944, ) _sym_db.RegisterEnumDescriptor(_TELEMETRYRESULT_RESULT) @@ -3423,6 +3423,13 @@ message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, serialized_options=b'\202\265\030\003NaN', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='timestamp_us', full_name='mavsdk.rpc.telemetry.Quaternion.timestamp_us', index=4, + number=5, type=4, cpp_type=4, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), ], extensions=[ ], @@ -3436,7 +3443,7 @@ oneofs=[ ], serialized_start=6379, - serialized_end=6471, + serialized_end=6493, ) @@ -3469,6 +3476,13 @@ message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, serialized_options=b'\202\265\030\003NaN', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='timestamp_us', full_name='mavsdk.rpc.telemetry.EulerAngle.timestamp_us', index=3, + number=4, type=4, cpp_type=4, label=1, + has_default_value=False, default_value=0, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), ], extensions=[ ], @@ -3481,8 +3495,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=6473, - serialized_end=6566, + serialized_start=6495, + serialized_end=6610, ) @@ -3527,8 +3541,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=6568, - serialized_end=6676, + serialized_start=6612, + serialized_end=6720, ) @@ -3566,8 +3580,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=6678, - serialized_end=6767, + serialized_start=6722, + serialized_end=6811, ) @@ -3605,8 +3619,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=6769, - serialized_end=6842, + serialized_start=6813, + serialized_end=6886, ) @@ -3679,8 +3693,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=6845, - serialized_end=7171, + serialized_start=6889, + serialized_end=7215, ) @@ -3725,8 +3739,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7173, - serialized_end=7295, + serialized_start=7217, + serialized_end=7339, ) @@ -3764,8 +3778,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7297, - serialized_end=7375, + serialized_start=7341, + serialized_end=7419, ) @@ -3803,8 +3817,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7377, - serialized_end=7440, + serialized_start=7421, + serialized_end=7484, ) @@ -3842,8 +3856,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7442, - serialized_end=7505, + serialized_start=7486, + serialized_end=7549, ) @@ -3874,8 +3888,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7507, - serialized_end=7546, + serialized_start=7551, + serialized_end=7590, ) @@ -3920,8 +3934,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7548, - serialized_end=7607, + serialized_start=7592, + serialized_end=7651, ) @@ -3966,8 +3980,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7609, - serialized_end=7662, + serialized_start=7653, + serialized_end=7706, ) @@ -4055,8 +4069,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=7665, - serialized_end=8285, + serialized_start=7709, + serialized_end=8329, ) @@ -4101,8 +4115,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8287, - serialized_end=8414, + serialized_start=8331, + serialized_end=8458, ) @@ -4147,8 +4161,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8416, - serialized_end=8505, + serialized_start=8460, + serialized_end=8549, ) @@ -4193,8 +4207,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8507, - serialized_end=8575, + serialized_start=8551, + serialized_end=8619, ) @@ -4232,8 +4246,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8577, - serialized_end=8704, + serialized_start=8621, + serialized_end=8748, ) @@ -4278,8 +4292,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8706, - serialized_end=8820, + serialized_start=8750, + serialized_end=8864, ) @@ -4324,8 +4338,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8822, - serialized_end=8942, + serialized_start=8866, + serialized_end=8986, ) @@ -4370,8 +4384,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=8944, - serialized_end=9049, + serialized_start=8988, + serialized_end=9093, ) @@ -4416,8 +4430,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=9051, - serialized_end=9162, + serialized_start=9095, + serialized_end=9206, ) @@ -4462,8 +4476,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=9164, - serialized_end=9273, + serialized_start=9208, + serialized_end=9317, ) @@ -4515,8 +4529,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=9276, - serialized_end=9521, + serialized_start=9320, + serialized_end=9565, ) @@ -4561,8 +4575,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=9523, - serialized_end=9632, + serialized_start=9567, + serialized_end=9676, ) @@ -4601,8 +4615,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=9635, - serialized_end=9900, + serialized_start=9679, + serialized_end=9944, ) _POSITIONRESPONSE.fields_by_name['position'].message_type = _POSITION @@ -5739,8 +5753,8 @@ index=0, serialized_options=None, create_key=_descriptor._internal_create_key, - serialized_start=10865, - serialized_end=16745, + serialized_start=10909, + serialized_end=16789, methods=[ _descriptor.MethodDescriptor( name='SubscribePosition', diff --git a/proto b/proto index 92b4e7bf..aa9dee2b 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 92b4e7bf0d9283bee75bd4e37d8c21bcec95c67a +Subproject commit aa9dee2b83622d5bb92c1f5b799d8a34b86feaed