diff --git a/MAVSDK_SERVER_VERSION b/MAVSDK_SERVER_VERSION index 31950dac..91d002b8 100644 --- a/MAVSDK_SERVER_VERSION +++ b/MAVSDK_SERVER_VERSION @@ -1 +1 @@ -v0.28.0 +v0.29.0 diff --git a/mavsdk/failure.py b/mavsdk/failure.py new file mode 100644 index 00000000..42f9888b --- /dev/null +++ b/mavsdk/failure.py @@ -0,0 +1,462 @@ +# -*- coding: utf-8 -*- +# DO NOT EDIT! This file is auto-generated from +# https://github.com/mavlink/MAVSDK-Python/tree/master/other/templates/py +from ._base import AsyncBase +from . import failure_pb2, failure_pb2_grpc +from enum import Enum + + +class FailureUnit(Enum): + """ + A failure unit. + + Values + ------ + SENSOR_GYRO + Gyro + + SENSOR_ACCEL + Accelerometer + + SENSOR_MAG + Magnetometer + + SENSOR_BARO + Barometer + + SENSOR_GPS + GPS + + SENSOR_OPTICAL_FLOW + Optical flow + + SENSOR_VIO + Visual inertial odometry + + SENSOR_DISTANCE_SENSOR + Distance sensor + + SENSOR_AIRSPEED + Airspeed + + SYSTEM_BATTERY + Battery + + SYSTEM_MOTOR + Motor + + SYSTEM_SERVO + Servo + + SYSTEM_AVOIDANCE + Avoidance + + SYSTEM_RC_SIGNAL + RC signal + + SYSTEM_MAVLINK_SIGNAL + MAVLink signal + + """ + + + SENSOR_GYRO = 0 + SENSOR_ACCEL = 1 + SENSOR_MAG = 2 + SENSOR_BARO = 3 + SENSOR_GPS = 4 + SENSOR_OPTICAL_FLOW = 5 + SENSOR_VIO = 6 + SENSOR_DISTANCE_SENSOR = 7 + SENSOR_AIRSPEED = 8 + SYSTEM_BATTERY = 9 + SYSTEM_MOTOR = 10 + SYSTEM_SERVO = 11 + SYSTEM_AVOIDANCE = 12 + SYSTEM_RC_SIGNAL = 13 + SYSTEM_MAVLINK_SIGNAL = 14 + + def translate_to_rpc(self): + if self == FailureUnit.SENSOR_GYRO: + return failure_pb2.FAILURE_UNIT_SENSOR_GYRO + if self == FailureUnit.SENSOR_ACCEL: + return failure_pb2.FAILURE_UNIT_SENSOR_ACCEL + if self == FailureUnit.SENSOR_MAG: + return failure_pb2.FAILURE_UNIT_SENSOR_MAG + if self == FailureUnit.SENSOR_BARO: + return failure_pb2.FAILURE_UNIT_SENSOR_BARO + if self == FailureUnit.SENSOR_GPS: + return failure_pb2.FAILURE_UNIT_SENSOR_GPS + if self == FailureUnit.SENSOR_OPTICAL_FLOW: + return failure_pb2.FAILURE_UNIT_SENSOR_OPTICAL_FLOW + if self == FailureUnit.SENSOR_VIO: + return failure_pb2.FAILURE_UNIT_SENSOR_VIO + if self == FailureUnit.SENSOR_DISTANCE_SENSOR: + return failure_pb2.FAILURE_UNIT_SENSOR_DISTANCE_SENSOR + if self == FailureUnit.SENSOR_AIRSPEED: + return failure_pb2.FAILURE_UNIT_SENSOR_AIRSPEED + if self == FailureUnit.SYSTEM_BATTERY: + return failure_pb2.FAILURE_UNIT_SYSTEM_BATTERY + if self == FailureUnit.SYSTEM_MOTOR: + return failure_pb2.FAILURE_UNIT_SYSTEM_MOTOR + if self == FailureUnit.SYSTEM_SERVO: + return failure_pb2.FAILURE_UNIT_SYSTEM_SERVO + if self == FailureUnit.SYSTEM_AVOIDANCE: + return failure_pb2.FAILURE_UNIT_SYSTEM_AVOIDANCE + if self == FailureUnit.SYSTEM_RC_SIGNAL: + return failure_pb2.FAILURE_UNIT_SYSTEM_RC_SIGNAL + if self == FailureUnit.SYSTEM_MAVLINK_SIGNAL: + return failure_pb2.FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL + + @staticmethod + def translate_from_rpc(rpc_enum_value): + """ Parses a gRPC response """ + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_GYRO: + return FailureUnit.SENSOR_GYRO + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_ACCEL: + return FailureUnit.SENSOR_ACCEL + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_MAG: + return FailureUnit.SENSOR_MAG + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_BARO: + return FailureUnit.SENSOR_BARO + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_GPS: + return FailureUnit.SENSOR_GPS + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_OPTICAL_FLOW: + return FailureUnit.SENSOR_OPTICAL_FLOW + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_VIO: + return FailureUnit.SENSOR_VIO + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_DISTANCE_SENSOR: + return FailureUnit.SENSOR_DISTANCE_SENSOR + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SENSOR_AIRSPEED: + return FailureUnit.SENSOR_AIRSPEED + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_BATTERY: + return FailureUnit.SYSTEM_BATTERY + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_MOTOR: + return FailureUnit.SYSTEM_MOTOR + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_SERVO: + return FailureUnit.SYSTEM_SERVO + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_AVOIDANCE: + return FailureUnit.SYSTEM_AVOIDANCE + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_RC_SIGNAL: + return FailureUnit.SYSTEM_RC_SIGNAL + if rpc_enum_value == failure_pb2.FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL: + return FailureUnit.SYSTEM_MAVLINK_SIGNAL + + def __str__(self): + return self.name + + +class FailureType(Enum): + """ + A failure type + + Values + ------ + OK + No failure injected, used to reset a previous failure + + OFF + Sets unit off, so completely non-responsive + + STUCK + Unit is stuck e.g. keeps reporting the same value + + GARBAGE + Unit is reporting complete garbage + + WRONG + Unit is consistently wrong + + SLOW + Unit is slow, so e.g. reporting at slower than expected rate + + DELAYED + Data of unit is delayed in time + + INTERMITTENT + Unit is sometimes working, sometimes not + + """ + + + OK = 0 + OFF = 1 + STUCK = 2 + GARBAGE = 3 + WRONG = 4 + SLOW = 5 + DELAYED = 6 + INTERMITTENT = 7 + + def translate_to_rpc(self): + if self == FailureType.OK: + return failure_pb2.FAILURE_TYPE_OK + if self == FailureType.OFF: + return failure_pb2.FAILURE_TYPE_OFF + if self == FailureType.STUCK: + return failure_pb2.FAILURE_TYPE_STUCK + if self == FailureType.GARBAGE: + return failure_pb2.FAILURE_TYPE_GARBAGE + if self == FailureType.WRONG: + return failure_pb2.FAILURE_TYPE_WRONG + if self == FailureType.SLOW: + return failure_pb2.FAILURE_TYPE_SLOW + if self == FailureType.DELAYED: + return failure_pb2.FAILURE_TYPE_DELAYED + if self == FailureType.INTERMITTENT: + return failure_pb2.FAILURE_TYPE_INTERMITTENT + + @staticmethod + def translate_from_rpc(rpc_enum_value): + """ Parses a gRPC response """ + if rpc_enum_value == failure_pb2.FAILURE_TYPE_OK: + return FailureType.OK + if rpc_enum_value == failure_pb2.FAILURE_TYPE_OFF: + return FailureType.OFF + if rpc_enum_value == failure_pb2.FAILURE_TYPE_STUCK: + return FailureType.STUCK + if rpc_enum_value == failure_pb2.FAILURE_TYPE_GARBAGE: + return FailureType.GARBAGE + if rpc_enum_value == failure_pb2.FAILURE_TYPE_WRONG: + return FailureType.WRONG + if rpc_enum_value == failure_pb2.FAILURE_TYPE_SLOW: + return FailureType.SLOW + if rpc_enum_value == failure_pb2.FAILURE_TYPE_DELAYED: + return FailureType.DELAYED + if rpc_enum_value == failure_pb2.FAILURE_TYPE_INTERMITTENT: + return FailureType.INTERMITTENT + + def __str__(self): + return self.name + + +class FailureResult: + """ + + + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result + + """ + + + + class Result(Enum): + """ + Possible results returned for failure requests. + + Values + ------ + UNKNOWN + Unknown result + + SUCCESS + Request succeeded + + NO_SYSTEM + No system is connected + + CONNECTION_ERROR + Connection error + + UNSUPPORTED + Failure not supported + + DENIED + Failure injection denied + + DISABLED + Failure injection is disabled + + TIMEOUT + Request timed out + + """ + + + UNKNOWN = 0 + SUCCESS = 1 + NO_SYSTEM = 2 + CONNECTION_ERROR = 3 + UNSUPPORTED = 4 + DENIED = 5 + DISABLED = 6 + TIMEOUT = 7 + + def translate_to_rpc(self): + if self == FailureResult.Result.UNKNOWN: + return failure_pb2.FailureResult.RESULT_UNKNOWN + if self == FailureResult.Result.SUCCESS: + return failure_pb2.FailureResult.RESULT_SUCCESS + if self == FailureResult.Result.NO_SYSTEM: + return failure_pb2.FailureResult.RESULT_NO_SYSTEM + if self == FailureResult.Result.CONNECTION_ERROR: + return failure_pb2.FailureResult.RESULT_CONNECTION_ERROR + if self == FailureResult.Result.UNSUPPORTED: + return failure_pb2.FailureResult.RESULT_UNSUPPORTED + if self == FailureResult.Result.DENIED: + return failure_pb2.FailureResult.RESULT_DENIED + if self == FailureResult.Result.DISABLED: + return failure_pb2.FailureResult.RESULT_DISABLED + if self == FailureResult.Result.TIMEOUT: + return failure_pb2.FailureResult.RESULT_TIMEOUT + + @staticmethod + def translate_from_rpc(rpc_enum_value): + """ Parses a gRPC response """ + if rpc_enum_value == failure_pb2.FailureResult.RESULT_UNKNOWN: + return FailureResult.Result.UNKNOWN + if rpc_enum_value == failure_pb2.FailureResult.RESULT_SUCCESS: + return FailureResult.Result.SUCCESS + if rpc_enum_value == failure_pb2.FailureResult.RESULT_NO_SYSTEM: + return FailureResult.Result.NO_SYSTEM + if rpc_enum_value == failure_pb2.FailureResult.RESULT_CONNECTION_ERROR: + return FailureResult.Result.CONNECTION_ERROR + if rpc_enum_value == failure_pb2.FailureResult.RESULT_UNSUPPORTED: + return FailureResult.Result.UNSUPPORTED + if rpc_enum_value == failure_pb2.FailureResult.RESULT_DENIED: + return FailureResult.Result.DENIED + if rpc_enum_value == failure_pb2.FailureResult.RESULT_DISABLED: + return FailureResult.Result.DISABLED + if rpc_enum_value == failure_pb2.FailureResult.RESULT_TIMEOUT: + return FailureResult.Result.TIMEOUT + + def __str__(self): + return self.name + + + def __init__( + self, + result, + result_str): + """ Initializes the FailureResult object """ + self.result = result + self.result_str = result_str + + def __equals__(self, to_compare): + """ Checks if two FailureResult are the same """ + try: + # Try to compare - this likely fails when it is compared to a non + # FailureResult object + return \ + (self.result == to_compare.result) and \ + (self.result_str == to_compare.result_str) + + except AttributeError: + return False + + def __str__(self): + """ FailureResult in string representation """ + struct_repr = ", ".join([ + "result: " + str(self.result), + "result_str: " + str(self.result_str) + ]) + + return f"FailureResult: [{struct_repr}]" + + @staticmethod + def translate_from_rpc(rpcFailureResult): + """ Translates a gRPC struct to the SDK equivalent """ + return FailureResult( + + FailureResult.Result.translate_from_rpc(rpcFailureResult.result), + + + rpcFailureResult.result_str + ) + + def translate_to_rpc(self, rpcFailureResult): + """ Translates this SDK object into its gRPC equivalent """ + + + + + rpcFailureResult.result = self.result.translate_to_rpc() + + + + + + rpcFailureResult.result_str = self.result_str + + + + + + +class FailureError(Exception): + """ Raised when a FailureResult is a fail code """ + + def __init__(self, result, origin, *params): + self._result = result + self._origin = origin + self._params = params + + def __str__(self): + return f"{self._result.result}: '{self._result.result_str}'; origin: {self._origin}; params: {self._params}" + + +class Failure(AsyncBase): + """ + Inject failures into system to test failsafes. + + Generated by dcsdkgen - MAVSDK Failure API + """ + + # Plugin name + name = "Failure" + + def _setup_stub(self, channel): + """ Setups the api stub """ + self._stub = failure_pb2_grpc.FailureServiceStub(channel) + + + def _extract_result(self, response): + """ Returns the response status and description """ + return FailureResult.translate_from_rpc(response.failure_result) + + + async def inject(self, failure_unit, failure_type, instance): + """ + Injects a failure. + + Parameters + ---------- + failure_unit : FailureUnit + The failure unit to send + + failure_type : FailureType + The failure type to send + + instance : int32_t + Instance to affect (0 for all) + + Raises + ------ + FailureError + If the request fails. The error contains the reason for the failure. + """ + + request = failure_pb2.InjectRequest() + + request.failure_unit = failure_unit.translate_to_rpc() + + + + request.failure_type = failure_type.translate_to_rpc() + + + request.instance = instance + response = await self._stub.Inject(request) + + + result = self._extract_result(response) + + if result.result is not FailureResult.Result.SUCCESS: + raise FailureError(result, "inject()", failure_unit, failure_type, instance) + \ No newline at end of file diff --git a/mavsdk/failure_pb2.py b/mavsdk/failure_pb2.py new file mode 100644 index 00000000..255526ee --- /dev/null +++ b/mavsdk/failure_pb2.py @@ -0,0 +1,394 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: failure/failure.proto + +from google.protobuf.internal import enum_type_wrapper +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + +from . import mavsdk_options_pb2 as mavsdk__options__pb2 + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='failure/failure.proto', + package='mavsdk.rpc.failure', + syntax='proto3', + serialized_options=b'\n\021io.mavsdk.failureB\014FailureProto', + serialized_pb=b'\n\x15\x66\x61ilure/failure.proto\x12\x12mavsdk.rpc.failure\x1a\x14mavsdk_options.proto\"\x8f\x01\n\rInjectRequest\x12\x35\n\x0c\x66\x61ilure_unit\x18\x01 \x01(\x0e\x32\x1f.mavsdk.rpc.failure.FailureUnit\x12\x35\n\x0c\x66\x61ilure_type\x18\x02 \x01(\x0e\x32\x1f.mavsdk.rpc.failure.FailureType\x12\x10\n\x08instance\x18\x03 \x01(\x05\"K\n\x0eInjectResponse\x12\x39\n\x0e\x66\x61ilure_result\x18\x01 \x01(\x0b\x32!.mavsdk.rpc.failure.FailureResult\"\x97\x02\n\rFailureResult\x12\x38\n\x06result\x18\x01 \x01(\x0e\x32(.mavsdk.rpc.failure.FailureResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xb7\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\x16\n\x12RESULT_UNSUPPORTED\x10\x04\x12\x11\n\rRESULT_DENIED\x10\x05\x12\x13\n\x0fRESULT_DISABLED\x10\x06\x12\x12\n\x0eRESULT_TIMEOUT\x10\x07*\xfd\x03\n\x0b\x46\x61ilureUnit\x12\x1c\n\x18\x46\x41ILURE_UNIT_SENSOR_GYRO\x10\x00\x12\x1d\n\x19\x46\x41ILURE_UNIT_SENSOR_ACCEL\x10\x01\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_MAG\x10\x02\x12\x1c\n\x18\x46\x41ILURE_UNIT_SENSOR_BARO\x10\x03\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_GPS\x10\x04\x12$\n FAILURE_UNIT_SENSOR_OPTICAL_FLOW\x10\x05\x12\x1b\n\x17\x46\x41ILURE_UNIT_SENSOR_VIO\x10\x06\x12\'\n#FAILURE_UNIT_SENSOR_DISTANCE_SENSOR\x10\x07\x12 \n\x1c\x46\x41ILURE_UNIT_SENSOR_AIRSPEED\x10\x08\x12\x1f\n\x1b\x46\x41ILURE_UNIT_SYSTEM_BATTERY\x10\x64\x12\x1d\n\x19\x46\x41ILURE_UNIT_SYSTEM_MOTOR\x10\x65\x12\x1d\n\x19\x46\x41ILURE_UNIT_SYSTEM_SERVO\x10\x66\x12!\n\x1d\x46\x41ILURE_UNIT_SYSTEM_AVOIDANCE\x10g\x12!\n\x1d\x46\x41ILURE_UNIT_SYSTEM_RC_SIGNAL\x10h\x12&\n\"FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL\x10i*\xd2\x01\n\x0b\x46\x61ilureType\x12\x13\n\x0f\x46\x41ILURE_TYPE_OK\x10\x00\x12\x14\n\x10\x46\x41ILURE_TYPE_OFF\x10\x01\x12\x16\n\x12\x46\x41ILURE_TYPE_STUCK\x10\x02\x12\x18\n\x14\x46\x41ILURE_TYPE_GARBAGE\x10\x03\x12\x16\n\x12\x46\x41ILURE_TYPE_WRONG\x10\x04\x12\x15\n\x11\x46\x41ILURE_TYPE_SLOW\x10\x05\x12\x18\n\x14\x46\x41ILURE_TYPE_DELAYED\x10\x06\x12\x1d\n\x19\x46\x41ILURE_TYPE_INTERMITTENT\x10\x07\x32g\n\x0e\x46\x61ilureService\x12U\n\x06Inject\x12!.mavsdk.rpc.failure.InjectRequest\x1a\".mavsdk.rpc.failure.InjectResponse\"\x04\x80\xb5\x18\x01\x42!\n\x11io.mavsdk.failureB\x0c\x46\x61ilureProtob\x06proto3' + , + dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) + +_FAILUREUNIT = _descriptor.EnumDescriptor( + name='FailureUnit', + full_name='mavsdk.rpc.failure.FailureUnit', + filename=None, + file=DESCRIPTOR, + values=[ + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_GYRO', index=0, number=0, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_ACCEL', index=1, number=1, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_MAG', index=2, number=2, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_BARO', index=3, number=3, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_GPS', index=4, number=4, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_OPTICAL_FLOW', index=5, number=5, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_VIO', index=6, number=6, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_DISTANCE_SENSOR', index=7, number=7, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SENSOR_AIRSPEED', index=8, number=8, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_BATTERY', index=9, number=100, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_MOTOR', index=10, number=101, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_SERVO', index=11, number=102, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_AVOIDANCE', index=12, number=103, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_RC_SIGNAL', index=13, number=104, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL', index=14, number=105, + serialized_options=None, + type=None), + ], + containing_type=None, + serialized_options=None, + serialized_start=573, + serialized_end=1082, +) +_sym_db.RegisterEnumDescriptor(_FAILUREUNIT) + +FailureUnit = enum_type_wrapper.EnumTypeWrapper(_FAILUREUNIT) +_FAILURETYPE = _descriptor.EnumDescriptor( + name='FailureType', + full_name='mavsdk.rpc.failure.FailureType', + filename=None, + file=DESCRIPTOR, + values=[ + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_OK', index=0, number=0, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_OFF', index=1, number=1, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_STUCK', index=2, number=2, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_GARBAGE', index=3, number=3, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_WRONG', index=4, number=4, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_SLOW', index=5, number=5, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_DELAYED', index=6, number=6, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='FAILURE_TYPE_INTERMITTENT', index=7, number=7, + serialized_options=None, + type=None), + ], + containing_type=None, + serialized_options=None, + serialized_start=1085, + serialized_end=1295, +) +_sym_db.RegisterEnumDescriptor(_FAILURETYPE) + +FailureType = enum_type_wrapper.EnumTypeWrapper(_FAILURETYPE) +FAILURE_UNIT_SENSOR_GYRO = 0 +FAILURE_UNIT_SENSOR_ACCEL = 1 +FAILURE_UNIT_SENSOR_MAG = 2 +FAILURE_UNIT_SENSOR_BARO = 3 +FAILURE_UNIT_SENSOR_GPS = 4 +FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5 +FAILURE_UNIT_SENSOR_VIO = 6 +FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7 +FAILURE_UNIT_SENSOR_AIRSPEED = 8 +FAILURE_UNIT_SYSTEM_BATTERY = 100 +FAILURE_UNIT_SYSTEM_MOTOR = 101 +FAILURE_UNIT_SYSTEM_SERVO = 102 +FAILURE_UNIT_SYSTEM_AVOIDANCE = 103 +FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104 +FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105 +FAILURE_TYPE_OK = 0 +FAILURE_TYPE_OFF = 1 +FAILURE_TYPE_STUCK = 2 +FAILURE_TYPE_GARBAGE = 3 +FAILURE_TYPE_WRONG = 4 +FAILURE_TYPE_SLOW = 5 +FAILURE_TYPE_DELAYED = 6 +FAILURE_TYPE_INTERMITTENT = 7 + + +_FAILURERESULT_RESULT = _descriptor.EnumDescriptor( + name='Result', + full_name='mavsdk.rpc.failure.FailureResult.Result', + filename=None, + file=DESCRIPTOR, + values=[ + _descriptor.EnumValueDescriptor( + name='RESULT_UNKNOWN', index=0, number=0, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_SUCCESS', index=1, number=1, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_NO_SYSTEM', index=2, number=2, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_CONNECTION_ERROR', index=3, number=3, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_UNSUPPORTED', index=4, number=4, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_DENIED', index=5, number=5, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_DISABLED', index=6, number=6, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_TIMEOUT', index=7, number=7, + serialized_options=None, + type=None), + ], + containing_type=None, + serialized_options=None, + serialized_start=387, + serialized_end=570, +) +_sym_db.RegisterEnumDescriptor(_FAILURERESULT_RESULT) + + +_INJECTREQUEST = _descriptor.Descriptor( + name='InjectRequest', + full_name='mavsdk.rpc.failure.InjectRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='failure_unit', full_name='mavsdk.rpc.failure.InjectRequest.failure_unit', 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), + _descriptor.FieldDescriptor( + name='failure_type', full_name='mavsdk.rpc.failure.InjectRequest.failure_type', index=1, + number=2, 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), + _descriptor.FieldDescriptor( + name='instance', full_name='mavsdk.rpc.failure.InjectRequest.instance', 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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=68, + serialized_end=211, +) + + +_INJECTRESPONSE = _descriptor.Descriptor( + name='InjectResponse', + full_name='mavsdk.rpc.failure.InjectResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='failure_result', full_name='mavsdk.rpc.failure.InjectResponse.failure_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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=213, + serialized_end=288, +) + + +_FAILURERESULT = _descriptor.Descriptor( + name='FailureResult', + full_name='mavsdk.rpc.failure.FailureResult', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='result', full_name='mavsdk.rpc.failure.FailureResult.result', 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), + _descriptor.FieldDescriptor( + name='result_str', full_name='mavsdk.rpc.failure.FailureResult.result_str', index=1, + number=2, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + _FAILURERESULT_RESULT, + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=291, + serialized_end=570, +) + +_INJECTREQUEST.fields_by_name['failure_unit'].enum_type = _FAILUREUNIT +_INJECTREQUEST.fields_by_name['failure_type'].enum_type = _FAILURETYPE +_INJECTRESPONSE.fields_by_name['failure_result'].message_type = _FAILURERESULT +_FAILURERESULT.fields_by_name['result'].enum_type = _FAILURERESULT_RESULT +_FAILURERESULT_RESULT.containing_type = _FAILURERESULT +DESCRIPTOR.message_types_by_name['InjectRequest'] = _INJECTREQUEST +DESCRIPTOR.message_types_by_name['InjectResponse'] = _INJECTRESPONSE +DESCRIPTOR.message_types_by_name['FailureResult'] = _FAILURERESULT +DESCRIPTOR.enum_types_by_name['FailureUnit'] = _FAILUREUNIT +DESCRIPTOR.enum_types_by_name['FailureType'] = _FAILURETYPE +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +InjectRequest = _reflection.GeneratedProtocolMessageType('InjectRequest', (_message.Message,), { + 'DESCRIPTOR' : _INJECTREQUEST, + '__module__' : 'failure.failure_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.failure.InjectRequest) + }) +_sym_db.RegisterMessage(InjectRequest) + +InjectResponse = _reflection.GeneratedProtocolMessageType('InjectResponse', (_message.Message,), { + 'DESCRIPTOR' : _INJECTRESPONSE, + '__module__' : 'failure.failure_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.failure.InjectResponse) + }) +_sym_db.RegisterMessage(InjectResponse) + +FailureResult = _reflection.GeneratedProtocolMessageType('FailureResult', (_message.Message,), { + 'DESCRIPTOR' : _FAILURERESULT, + '__module__' : 'failure.failure_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.failure.FailureResult) + }) +_sym_db.RegisterMessage(FailureResult) + + +DESCRIPTOR._options = None + +_FAILURESERVICE = _descriptor.ServiceDescriptor( + name='FailureService', + full_name='mavsdk.rpc.failure.FailureService', + file=DESCRIPTOR, + index=0, + serialized_options=None, + serialized_start=1297, + serialized_end=1400, + methods=[ + _descriptor.MethodDescriptor( + name='Inject', + full_name='mavsdk.rpc.failure.FailureService.Inject', + index=0, + containing_service=None, + input_type=_INJECTREQUEST, + output_type=_INJECTRESPONSE, + serialized_options=b'\200\265\030\001', + ), +]) +_sym_db.RegisterServiceDescriptor(_FAILURESERVICE) + +DESCRIPTOR.services_by_name['FailureService'] = _FAILURESERVICE + +# @@protoc_insertion_point(module_scope) diff --git a/mavsdk/failure_pb2_grpc.py b/mavsdk/failure_pb2_grpc.py new file mode 100644 index 00000000..fab04af1 --- /dev/null +++ b/mavsdk/failure_pb2_grpc.py @@ -0,0 +1,68 @@ +# Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! +import grpc + +from . import failure_pb2 as failure_dot_failure__pb2 + + +class FailureServiceStub(object): + """Inject failures into system to test failsafes. + """ + + def __init__(self, channel): + """Constructor. + + Args: + channel: A grpc.Channel. + """ + self.Inject = channel.unary_unary( + '/mavsdk.rpc.failure.FailureService/Inject', + request_serializer=failure_dot_failure__pb2.InjectRequest.SerializeToString, + response_deserializer=failure_dot_failure__pb2.InjectResponse.FromString, + ) + + +class FailureServiceServicer(object): + """Inject failures into system to test failsafes. + """ + + def Inject(self, request, context): + """Injects a failure. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + +def add_FailureServiceServicer_to_server(servicer, server): + rpc_method_handlers = { + 'Inject': grpc.unary_unary_rpc_method_handler( + servicer.Inject, + request_deserializer=failure_dot_failure__pb2.InjectRequest.FromString, + response_serializer=failure_dot_failure__pb2.InjectResponse.SerializeToString, + ), + } + generic_handler = grpc.method_handlers_generic_handler( + 'mavsdk.rpc.failure.FailureService', rpc_method_handlers) + server.add_generic_rpc_handlers((generic_handler,)) + + + # This class is part of an EXPERIMENTAL API. +class FailureService(object): + """Inject failures into system to test failsafes. + """ + + @staticmethod + def Inject(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.failure.FailureService/Inject', + failure_dot_failure__pb2.InjectRequest.SerializeToString, + failure_dot_failure__pb2.InjectResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/mavsdk/ftp.py b/mavsdk/ftp.py index 23538a25..a991459d 100644 --- a/mavsdk/ftp.py +++ b/mavsdk/ftp.py @@ -638,13 +638,13 @@ async def set_root_directory(self, root_dir): raise FtpError(result, "set_root_directory()", root_dir) - async def set_target_component_id(self, component_id): + async def set_target_compid(self, compid): """ Set target component ID. By default it is the autopilot. Parameters ---------- - component_id : uint32_t + compid : uint32_t The component ID to set. Raises @@ -653,33 +653,33 @@ async def set_target_component_id(self, component_id): If the request fails. The error contains the reason for the failure. """ - request = ftp_pb2.SetTargetComponentIdRequest() - request.component_id = component_id - response = await self._stub.SetTargetComponentId(request) + request = ftp_pb2.SetTargetCompidRequest() + request.compid = compid + response = await self._stub.SetTargetCompid(request) result = self._extract_result(response) if result.result is not FtpResult.Result.SUCCESS: - raise FtpError(result, "set_target_component_id()", component_id) + raise FtpError(result, "set_target_compid()", compid) - async def get_our_component_id(self): + async def get_our_compid(self): """ Get our own component ID. Returns ------- - component_id : uint32_t + compid : uint32_t Our component ID. """ - request = ftp_pb2.GetOurComponentIdRequest() - response = await self._stub.GetOurComponentId(request) + request = ftp_pb2.GetOurCompidRequest() + response = await self._stub.GetOurCompid(request) - return response.component_id + return response.compid \ No newline at end of file diff --git a/mavsdk/ftp_pb2.py b/mavsdk/ftp_pb2.py index 490bfda8..f8d094e8 100644 --- a/mavsdk/ftp_pb2.py +++ b/mavsdk/ftp_pb2.py @@ -19,7 +19,7 @@ package='mavsdk.rpc.ftp', syntax='proto3', serialized_options=b'\n\rio.mavsdk.ftpB\010FtpProto', - serialized_pb=b'\n\rftp/ftp.proto\x12\x0emavsdk.rpc.ftp\x1a\x14mavsdk_options.proto\"\x0e\n\x0cResetRequest\">\n\rResetResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"G\n\x18SubscribeDownloadRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\x12\x11\n\tlocal_dir\x18\x02 \x01(\t\"v\n\x10\x44ownloadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"E\n\x16SubscribeUploadRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x12\n\nremote_dir\x18\x02 \x01(\t\"t\n\x0eUploadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"*\n\x14ListDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"U\n\x15ListDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\r\n\x05paths\x18\x02 \x03(\t\",\n\x16\x43reateDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17\x43reateDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\",\n\x16RemoveDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17RemoveDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"-\n\x11RemoveFileRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\"C\n\x12RemoveFileResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"A\n\rRenameRequest\x12\x18\n\x10remote_from_path\x18\x01 \x01(\t\x12\x16\n\x0eremote_to_path\x18\x02 \x01(\t\"?\n\x0eRenameResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"M\n\x18\x41reFilesIdenticalRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x18\n\x10remote_file_path\x18\x02 \x01(\t\"a\n\x19\x41reFilesIdenticalResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x15\n\rare_identical\x18\x02 \x01(\x08\"+\n\x17SetRootDirectoryRequest\x12\x10\n\x08root_dir\x18\x01 \x01(\t\"I\n\x18SetRootDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"3\n\x1bSetTargetComponentIdRequest\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\r\"M\n\x1cSetTargetComponentIdResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"\x1a\n\x18GetOurComponentIdRequest\"1\n\x19GetOurComponentIdResponse\x12\x14\n\x0c\x63omponent_id\x18\x01 \x01(\r\">\n\x0cProgressData\x12\x19\n\x11\x62ytes_transferred\x18\x01 \x01(\r\x12\x13\n\x0btotal_bytes\x18\x02 \x01(\r\"\xf8\x02\n\tFtpResult\x12\x30\n\x06result\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.ftp.FtpResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa4\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x18\n\x14RESULT_FILE_IO_ERROR\x10\x05\x12\x16\n\x12RESULT_FILE_EXISTS\x10\x06\x12\x1e\n\x1aRESULT_FILE_DOES_NOT_EXIST\x10\x07\x12\x19\n\x15RESULT_FILE_PROTECTED\x10\x08\x12\x1c\n\x18RESULT_INVALID_PARAMETER\x10\t\x12\x16\n\x12RESULT_UNSUPPORTED\x10\n\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x0b\x32\xbc\t\n\nFtpService\x12J\n\x05Reset\x12\x1c.mavsdk.rpc.ftp.ResetRequest\x1a\x1d.mavsdk.rpc.ftp.ResetResponse\"\x04\x80\xb5\x18\x00\x12k\n\x11SubscribeDownload\x12(.mavsdk.rpc.ftp.SubscribeDownloadRequest\x1a .mavsdk.rpc.ftp.DownloadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x65\n\x0fSubscribeUpload\x12&.mavsdk.rpc.ftp.SubscribeUploadRequest\x1a\x1e.mavsdk.rpc.ftp.UploadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12^\n\rListDirectory\x12$.mavsdk.rpc.ftp.ListDirectoryRequest\x1a%.mavsdk.rpc.ftp.ListDirectoryResponse\"\x00\x12\x64\n\x0f\x43reateDirectory\x12&.mavsdk.rpc.ftp.CreateDirectoryRequest\x1a\'.mavsdk.rpc.ftp.CreateDirectoryResponse\"\x00\x12\x64\n\x0fRemoveDirectory\x12&.mavsdk.rpc.ftp.RemoveDirectoryRequest\x1a\'.mavsdk.rpc.ftp.RemoveDirectoryResponse\"\x00\x12U\n\nRemoveFile\x12!.mavsdk.rpc.ftp.RemoveFileRequest\x1a\".mavsdk.rpc.ftp.RemoveFileResponse\"\x00\x12I\n\x06Rename\x12\x1d.mavsdk.rpc.ftp.RenameRequest\x1a\x1e.mavsdk.rpc.ftp.RenameResponse\"\x00\x12j\n\x11\x41reFilesIdentical\x12(.mavsdk.rpc.ftp.AreFilesIdenticalRequest\x1a).mavsdk.rpc.ftp.AreFilesIdenticalResponse\"\x00\x12k\n\x10SetRootDirectory\x12\'.mavsdk.rpc.ftp.SetRootDirectoryRequest\x1a(.mavsdk.rpc.ftp.SetRootDirectoryResponse\"\x04\x80\xb5\x18\x01\x12w\n\x14SetTargetComponentId\x12+.mavsdk.rpc.ftp.SetTargetComponentIdRequest\x1a,.mavsdk.rpc.ftp.SetTargetComponentIdResponse\"\x04\x80\xb5\x18\x01\x12n\n\x11GetOurComponentId\x12(.mavsdk.rpc.ftp.GetOurComponentIdRequest\x1a).mavsdk.rpc.ftp.GetOurComponentIdResponse\"\x04\x80\xb5\x18\x01\x42\x19\n\rio.mavsdk.ftpB\x08\x46tpProtob\x06proto3' + serialized_pb=b'\n\rftp/ftp.proto\x12\x0emavsdk.rpc.ftp\x1a\x14mavsdk_options.proto\"\x0e\n\x0cResetRequest\">\n\rResetResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"G\n\x18SubscribeDownloadRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\x12\x11\n\tlocal_dir\x18\x02 \x01(\t\"v\n\x10\x44ownloadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"E\n\x16SubscribeUploadRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x12\n\nremote_dir\x18\x02 \x01(\t\"t\n\x0eUploadResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x33\n\rprogress_data\x18\x02 \x01(\x0b\x32\x1c.mavsdk.rpc.ftp.ProgressData\"*\n\x14ListDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"U\n\x15ListDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\r\n\x05paths\x18\x02 \x03(\t\",\n\x16\x43reateDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17\x43reateDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\",\n\x16RemoveDirectoryRequest\x12\x12\n\nremote_dir\x18\x01 \x01(\t\"H\n\x17RemoveDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"-\n\x11RemoveFileRequest\x12\x18\n\x10remote_file_path\x18\x01 \x01(\t\"C\n\x12RemoveFileResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"A\n\rRenameRequest\x12\x18\n\x10remote_from_path\x18\x01 \x01(\t\x12\x16\n\x0eremote_to_path\x18\x02 \x01(\t\"?\n\x0eRenameResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"M\n\x18\x41reFilesIdenticalRequest\x12\x17\n\x0flocal_file_path\x18\x01 \x01(\t\x12\x18\n\x10remote_file_path\x18\x02 \x01(\t\"a\n\x19\x41reFilesIdenticalResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\x12\x15\n\rare_identical\x18\x02 \x01(\x08\"+\n\x17SetRootDirectoryRequest\x12\x10\n\x08root_dir\x18\x01 \x01(\t\"I\n\x18SetRootDirectoryResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"(\n\x16SetTargetCompidRequest\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\"H\n\x17SetTargetCompidResponse\x12-\n\nftp_result\x18\x01 \x01(\x0b\x32\x19.mavsdk.rpc.ftp.FtpResult\"\x15\n\x13GetOurCompidRequest\"&\n\x14GetOurCompidResponse\x12\x0e\n\x06\x63ompid\x18\x01 \x01(\r\">\n\x0cProgressData\x12\x19\n\x11\x62ytes_transferred\x18\x01 \x01(\r\x12\x13\n\x0btotal_bytes\x18\x02 \x01(\r\"\xf8\x02\n\tFtpResult\x12\x30\n\x06result\x18\x01 \x01(\x0e\x32 .mavsdk.rpc.ftp.FtpResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xa4\x02\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x0f\n\x0bRESULT_NEXT\x10\x02\x12\x12\n\x0eRESULT_TIMEOUT\x10\x03\x12\x0f\n\x0bRESULT_BUSY\x10\x04\x12\x18\n\x14RESULT_FILE_IO_ERROR\x10\x05\x12\x16\n\x12RESULT_FILE_EXISTS\x10\x06\x12\x1e\n\x1aRESULT_FILE_DOES_NOT_EXIST\x10\x07\x12\x19\n\x15RESULT_FILE_PROTECTED\x10\x08\x12\x1c\n\x18RESULT_INVALID_PARAMETER\x10\t\x12\x16\n\x12RESULT_UNSUPPORTED\x10\n\x12\x19\n\x15RESULT_PROTOCOL_ERROR\x10\x0b\x32\x9e\t\n\nFtpService\x12J\n\x05Reset\x12\x1c.mavsdk.rpc.ftp.ResetRequest\x1a\x1d.mavsdk.rpc.ftp.ResetResponse\"\x04\x80\xb5\x18\x00\x12k\n\x11SubscribeDownload\x12(.mavsdk.rpc.ftp.SubscribeDownloadRequest\x1a .mavsdk.rpc.ftp.DownloadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12\x65\n\x0fSubscribeUpload\x12&.mavsdk.rpc.ftp.SubscribeUploadRequest\x1a\x1e.mavsdk.rpc.ftp.UploadResponse\"\x08\x80\xb5\x18\x00\x88\xb5\x18\x01\x30\x01\x12^\n\rListDirectory\x12$.mavsdk.rpc.ftp.ListDirectoryRequest\x1a%.mavsdk.rpc.ftp.ListDirectoryResponse\"\x00\x12\x64\n\x0f\x43reateDirectory\x12&.mavsdk.rpc.ftp.CreateDirectoryRequest\x1a\'.mavsdk.rpc.ftp.CreateDirectoryResponse\"\x00\x12\x64\n\x0fRemoveDirectory\x12&.mavsdk.rpc.ftp.RemoveDirectoryRequest\x1a\'.mavsdk.rpc.ftp.RemoveDirectoryResponse\"\x00\x12U\n\nRemoveFile\x12!.mavsdk.rpc.ftp.RemoveFileRequest\x1a\".mavsdk.rpc.ftp.RemoveFileResponse\"\x00\x12I\n\x06Rename\x12\x1d.mavsdk.rpc.ftp.RenameRequest\x1a\x1e.mavsdk.rpc.ftp.RenameResponse\"\x00\x12j\n\x11\x41reFilesIdentical\x12(.mavsdk.rpc.ftp.AreFilesIdenticalRequest\x1a).mavsdk.rpc.ftp.AreFilesIdenticalResponse\"\x00\x12k\n\x10SetRootDirectory\x12\'.mavsdk.rpc.ftp.SetRootDirectoryRequest\x1a(.mavsdk.rpc.ftp.SetRootDirectoryResponse\"\x04\x80\xb5\x18\x01\x12h\n\x0fSetTargetCompid\x12&.mavsdk.rpc.ftp.SetTargetCompidRequest\x1a\'.mavsdk.rpc.ftp.SetTargetCompidResponse\"\x04\x80\xb5\x18\x01\x12_\n\x0cGetOurCompid\x12#.mavsdk.rpc.ftp.GetOurCompidRequest\x1a$.mavsdk.rpc.ftp.GetOurCompidResponse\"\x04\x80\xb5\x18\x01\x42\x19\n\rio.mavsdk.ftpB\x08\x46tpProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -82,8 +82,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=1794, - serialized_end=2086, + serialized_start=1762, + serialized_end=2054, ) _sym_db.RegisterEnumDescriptor(_FTPRESULT_RESULT) @@ -757,15 +757,15 @@ ) -_SETTARGETCOMPONENTIDREQUEST = _descriptor.Descriptor( - name='SetTargetComponentIdRequest', - full_name='mavsdk.rpc.ftp.SetTargetComponentIdRequest', +_SETTARGETCOMPIDREQUEST = _descriptor.Descriptor( + name='SetTargetCompidRequest', + full_name='mavsdk.rpc.ftp.SetTargetCompidRequest', filename=None, file=DESCRIPTOR, containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='component_id', full_name='mavsdk.rpc.ftp.SetTargetComponentIdRequest.component_id', index=0, + name='compid', full_name='mavsdk.rpc.ftp.SetTargetCompidRequest.compid', index=0, number=1, type=13, cpp_type=3, label=1, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, @@ -784,19 +784,19 @@ oneofs=[ ], serialized_start=1434, - serialized_end=1485, + serialized_end=1474, ) -_SETTARGETCOMPONENTIDRESPONSE = _descriptor.Descriptor( - name='SetTargetComponentIdResponse', - full_name='mavsdk.rpc.ftp.SetTargetComponentIdResponse', +_SETTARGETCOMPIDRESPONSE = _descriptor.Descriptor( + name='SetTargetCompidResponse', + full_name='mavsdk.rpc.ftp.SetTargetCompidResponse', filename=None, file=DESCRIPTOR, containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='ftp_result', full_name='mavsdk.rpc.ftp.SetTargetComponentIdResponse.ftp_result', index=0, + name='ftp_result', full_name='mavsdk.rpc.ftp.SetTargetCompidResponse.ftp_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, @@ -814,14 +814,14 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1487, - serialized_end=1564, + serialized_start=1476, + serialized_end=1548, ) -_GETOURCOMPONENTIDREQUEST = _descriptor.Descriptor( - name='GetOurComponentIdRequest', - full_name='mavsdk.rpc.ftp.GetOurComponentIdRequest', +_GETOURCOMPIDREQUEST = _descriptor.Descriptor( + name='GetOurCompidRequest', + full_name='mavsdk.rpc.ftp.GetOurCompidRequest', filename=None, file=DESCRIPTOR, containing_type=None, @@ -838,20 +838,20 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1566, - serialized_end=1592, + serialized_start=1550, + serialized_end=1571, ) -_GETOURCOMPONENTIDRESPONSE = _descriptor.Descriptor( - name='GetOurComponentIdResponse', - full_name='mavsdk.rpc.ftp.GetOurComponentIdResponse', +_GETOURCOMPIDRESPONSE = _descriptor.Descriptor( + name='GetOurCompidResponse', + full_name='mavsdk.rpc.ftp.GetOurCompidResponse', filename=None, file=DESCRIPTOR, containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='component_id', full_name='mavsdk.rpc.ftp.GetOurComponentIdResponse.component_id', index=0, + name='compid', full_name='mavsdk.rpc.ftp.GetOurCompidResponse.compid', index=0, number=1, type=13, cpp_type=3, label=1, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, @@ -869,8 +869,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1594, - serialized_end=1643, + serialized_start=1573, + serialized_end=1611, ) @@ -907,8 +907,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1645, - serialized_end=1707, + serialized_start=1613, + serialized_end=1675, ) @@ -946,8 +946,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1710, - serialized_end=2086, + serialized_start=1678, + serialized_end=2054, ) _RESETRESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT @@ -962,7 +962,7 @@ _RENAMERESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT _AREFILESIDENTICALRESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT _SETROOTDIRECTORYRESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT -_SETTARGETCOMPONENTIDRESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT +_SETTARGETCOMPIDRESPONSE.fields_by_name['ftp_result'].message_type = _FTPRESULT _FTPRESULT.fields_by_name['result'].enum_type = _FTPRESULT_RESULT _FTPRESULT_RESULT.containing_type = _FTPRESULT DESCRIPTOR.message_types_by_name['ResetRequest'] = _RESETREQUEST @@ -985,10 +985,10 @@ DESCRIPTOR.message_types_by_name['AreFilesIdenticalResponse'] = _AREFILESIDENTICALRESPONSE DESCRIPTOR.message_types_by_name['SetRootDirectoryRequest'] = _SETROOTDIRECTORYREQUEST DESCRIPTOR.message_types_by_name['SetRootDirectoryResponse'] = _SETROOTDIRECTORYRESPONSE -DESCRIPTOR.message_types_by_name['SetTargetComponentIdRequest'] = _SETTARGETCOMPONENTIDREQUEST -DESCRIPTOR.message_types_by_name['SetTargetComponentIdResponse'] = _SETTARGETCOMPONENTIDRESPONSE -DESCRIPTOR.message_types_by_name['GetOurComponentIdRequest'] = _GETOURCOMPONENTIDREQUEST -DESCRIPTOR.message_types_by_name['GetOurComponentIdResponse'] = _GETOURCOMPONENTIDRESPONSE +DESCRIPTOR.message_types_by_name['SetTargetCompidRequest'] = _SETTARGETCOMPIDREQUEST +DESCRIPTOR.message_types_by_name['SetTargetCompidResponse'] = _SETTARGETCOMPIDRESPONSE +DESCRIPTOR.message_types_by_name['GetOurCompidRequest'] = _GETOURCOMPIDREQUEST +DESCRIPTOR.message_types_by_name['GetOurCompidResponse'] = _GETOURCOMPIDRESPONSE DESCRIPTOR.message_types_by_name['ProgressData'] = _PROGRESSDATA DESCRIPTOR.message_types_by_name['FtpResult'] = _FTPRESULT _sym_db.RegisterFileDescriptor(DESCRIPTOR) @@ -1133,33 +1133,33 @@ }) _sym_db.RegisterMessage(SetRootDirectoryResponse) -SetTargetComponentIdRequest = _reflection.GeneratedProtocolMessageType('SetTargetComponentIdRequest', (_message.Message,), { - 'DESCRIPTOR' : _SETTARGETCOMPONENTIDREQUEST, +SetTargetCompidRequest = _reflection.GeneratedProtocolMessageType('SetTargetCompidRequest', (_message.Message,), { + 'DESCRIPTOR' : _SETTARGETCOMPIDREQUEST, '__module__' : 'ftp.ftp_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetComponentIdRequest) + # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidRequest) }) -_sym_db.RegisterMessage(SetTargetComponentIdRequest) +_sym_db.RegisterMessage(SetTargetCompidRequest) -SetTargetComponentIdResponse = _reflection.GeneratedProtocolMessageType('SetTargetComponentIdResponse', (_message.Message,), { - 'DESCRIPTOR' : _SETTARGETCOMPONENTIDRESPONSE, +SetTargetCompidResponse = _reflection.GeneratedProtocolMessageType('SetTargetCompidResponse', (_message.Message,), { + 'DESCRIPTOR' : _SETTARGETCOMPIDRESPONSE, '__module__' : 'ftp.ftp_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetComponentIdResponse) + # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.SetTargetCompidResponse) }) -_sym_db.RegisterMessage(SetTargetComponentIdResponse) +_sym_db.RegisterMessage(SetTargetCompidResponse) -GetOurComponentIdRequest = _reflection.GeneratedProtocolMessageType('GetOurComponentIdRequest', (_message.Message,), { - 'DESCRIPTOR' : _GETOURCOMPONENTIDREQUEST, +GetOurCompidRequest = _reflection.GeneratedProtocolMessageType('GetOurCompidRequest', (_message.Message,), { + 'DESCRIPTOR' : _GETOURCOMPIDREQUEST, '__module__' : 'ftp.ftp_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurComponentIdRequest) + # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurCompidRequest) }) -_sym_db.RegisterMessage(GetOurComponentIdRequest) +_sym_db.RegisterMessage(GetOurCompidRequest) -GetOurComponentIdResponse = _reflection.GeneratedProtocolMessageType('GetOurComponentIdResponse', (_message.Message,), { - 'DESCRIPTOR' : _GETOURCOMPONENTIDRESPONSE, +GetOurCompidResponse = _reflection.GeneratedProtocolMessageType('GetOurCompidResponse', (_message.Message,), { + 'DESCRIPTOR' : _GETOURCOMPIDRESPONSE, '__module__' : 'ftp.ftp_pb2' - # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurComponentIdResponse) + # @@protoc_insertion_point(class_scope:mavsdk.rpc.ftp.GetOurCompidResponse) }) -_sym_db.RegisterMessage(GetOurComponentIdResponse) +_sym_db.RegisterMessage(GetOurCompidResponse) ProgressData = _reflection.GeneratedProtocolMessageType('ProgressData', (_message.Message,), { 'DESCRIPTOR' : _PROGRESSDATA, @@ -1184,8 +1184,8 @@ file=DESCRIPTOR, index=0, serialized_options=None, - serialized_start=2089, - serialized_end=3301, + serialized_start=2057, + serialized_end=3239, methods=[ _descriptor.MethodDescriptor( name='Reset', @@ -1278,21 +1278,21 @@ serialized_options=b'\200\265\030\001', ), _descriptor.MethodDescriptor( - name='SetTargetComponentId', - full_name='mavsdk.rpc.ftp.FtpService.SetTargetComponentId', + name='SetTargetCompid', + full_name='mavsdk.rpc.ftp.FtpService.SetTargetCompid', index=10, containing_service=None, - input_type=_SETTARGETCOMPONENTIDREQUEST, - output_type=_SETTARGETCOMPONENTIDRESPONSE, + input_type=_SETTARGETCOMPIDREQUEST, + output_type=_SETTARGETCOMPIDRESPONSE, serialized_options=b'\200\265\030\001', ), _descriptor.MethodDescriptor( - name='GetOurComponentId', - full_name='mavsdk.rpc.ftp.FtpService.GetOurComponentId', + name='GetOurCompid', + full_name='mavsdk.rpc.ftp.FtpService.GetOurCompid', index=11, containing_service=None, - input_type=_GETOURCOMPONENTIDREQUEST, - output_type=_GETOURCOMPONENTIDRESPONSE, + input_type=_GETOURCOMPIDREQUEST, + output_type=_GETOURCOMPIDRESPONSE, serialized_options=b'\200\265\030\001', ), ]) diff --git a/mavsdk/ftp_pb2_grpc.py b/mavsdk/ftp_pb2_grpc.py index 0c5e838d..99dc6417 100644 --- a/mavsdk/ftp_pb2_grpc.py +++ b/mavsdk/ftp_pb2_grpc.py @@ -65,15 +65,15 @@ def __init__(self, channel): request_serializer=ftp_dot_ftp__pb2.SetRootDirectoryRequest.SerializeToString, response_deserializer=ftp_dot_ftp__pb2.SetRootDirectoryResponse.FromString, ) - self.SetTargetComponentId = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/SetTargetComponentId', - request_serializer=ftp_dot_ftp__pb2.SetTargetComponentIdRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.SetTargetComponentIdResponse.FromString, + self.SetTargetCompid = channel.unary_unary( + '/mavsdk.rpc.ftp.FtpService/SetTargetCompid', + request_serializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.FromString, ) - self.GetOurComponentId = channel.unary_unary( - '/mavsdk.rpc.ftp.FtpService/GetOurComponentId', - request_serializer=ftp_dot_ftp__pb2.GetOurComponentIdRequest.SerializeToString, - response_deserializer=ftp_dot_ftp__pb2.GetOurComponentIdResponse.FromString, + self.GetOurCompid = channel.unary_unary( + '/mavsdk.rpc.ftp.FtpService/GetOurCompid', + request_serializer=ftp_dot_ftp__pb2.GetOurCompidRequest.SerializeToString, + response_deserializer=ftp_dot_ftp__pb2.GetOurCompidResponse.FromString, ) @@ -162,7 +162,7 @@ def SetRootDirectory(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') - def SetTargetComponentId(self, request, context): + def SetTargetCompid(self, request, context): """ Set target component ID. By default it is the autopilot. """ @@ -170,7 +170,7 @@ def SetTargetComponentId(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') - def GetOurComponentId(self, request, context): + def GetOurCompid(self, request, context): """ Get our own component ID. """ @@ -231,15 +231,15 @@ def add_FtpServiceServicer_to_server(servicer, server): request_deserializer=ftp_dot_ftp__pb2.SetRootDirectoryRequest.FromString, response_serializer=ftp_dot_ftp__pb2.SetRootDirectoryResponse.SerializeToString, ), - 'SetTargetComponentId': grpc.unary_unary_rpc_method_handler( - servicer.SetTargetComponentId, - request_deserializer=ftp_dot_ftp__pb2.SetTargetComponentIdRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.SetTargetComponentIdResponse.SerializeToString, + 'SetTargetCompid': grpc.unary_unary_rpc_method_handler( + servicer.SetTargetCompid, + request_deserializer=ftp_dot_ftp__pb2.SetTargetCompidRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.SetTargetCompidResponse.SerializeToString, ), - 'GetOurComponentId': grpc.unary_unary_rpc_method_handler( - servicer.GetOurComponentId, - request_deserializer=ftp_dot_ftp__pb2.GetOurComponentIdRequest.FromString, - response_serializer=ftp_dot_ftp__pb2.GetOurComponentIdResponse.SerializeToString, + 'GetOurCompid': grpc.unary_unary_rpc_method_handler( + servicer.GetOurCompid, + request_deserializer=ftp_dot_ftp__pb2.GetOurCompidRequest.FromString, + response_serializer=ftp_dot_ftp__pb2.GetOurCompidResponse.SerializeToString, ), } generic_handler = grpc.method_handlers_generic_handler( @@ -414,7 +414,7 @@ def SetRootDirectory(request, call_credentials, compression, wait_for_ready, timeout, metadata) @staticmethod - def SetTargetComponentId(request, + def SetTargetCompid(request, target, options=(), channel_credentials=None, @@ -423,14 +423,14 @@ def SetTargetComponentId(request, wait_for_ready=None, timeout=None, metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.ftp.FtpService/SetTargetComponentId', - ftp_dot_ftp__pb2.SetTargetComponentIdRequest.SerializeToString, - ftp_dot_ftp__pb2.SetTargetComponentIdResponse.FromString, + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.ftp.FtpService/SetTargetCompid', + ftp_dot_ftp__pb2.SetTargetCompidRequest.SerializeToString, + ftp_dot_ftp__pb2.SetTargetCompidResponse.FromString, options, channel_credentials, call_credentials, compression, wait_for_ready, timeout, metadata) @staticmethod - def GetOurComponentId(request, + def GetOurCompid(request, target, options=(), channel_credentials=None, @@ -439,8 +439,8 @@ def GetOurComponentId(request, wait_for_ready=None, timeout=None, metadata=None): - return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.ftp.FtpService/GetOurComponentId', - ftp_dot_ftp__pb2.GetOurComponentIdRequest.SerializeToString, - ftp_dot_ftp__pb2.GetOurComponentIdResponse.FromString, + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.ftp.FtpService/GetOurCompid', + ftp_dot_ftp__pb2.GetOurCompidRequest.SerializeToString, + ftp_dot_ftp__pb2.GetOurCompidResponse.FromString, options, channel_credentials, call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/mavsdk/info.py b/mavsdk/info.py index a5190dad..f847eb4c 100644 --- a/mavsdk/info.py +++ b/mavsdk/info.py @@ -723,4 +723,32 @@ async def get_version(self): return Version.translate_from_rpc(response.version) - \ No newline at end of file + + + async def get_speed_factor(self): + """ + Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). + + Returns + ------- + speed_factor : double + Speed factor of simulation + + Raises + ------ + InfoError + If the request fails. The error contains the reason for the failure. + """ + + request = info_pb2.GetSpeedFactorRequest() + response = await self._stub.GetSpeedFactor(request) + + + result = self._extract_result(response) + + if result.result is not InfoResult.Result.SUCCESS: + raise InfoError(result, "get_speed_factor()") + + + return response.speed_factor + \ No newline at end of file diff --git a/mavsdk/info_pb2.py b/mavsdk/info_pb2.py index 1f1dc160..895f13cd 100644 --- a/mavsdk/info_pb2.py +++ b/mavsdk/info_pb2.py @@ -19,7 +19,7 @@ package='mavsdk.rpc.info', syntax='proto3', serialized_options=b'\n\016io.mavsdk.infoB\tInfoProto', - serialized_pb=b'\n\x0finfo/info.proto\x12\x0fmavsdk.rpc.info\x1a\x14mavsdk_options.proto\"\x1d\n\x1bGetFlightInformationRequest\"\x82\x01\n\x1cGetFlightInformationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x30\n\x0b\x66light_info\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo\"\x1a\n\x18GetIdentificationRequest\"\x86\x01\n\x19GetIdentificationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x37\n\x0eidentification\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.info.Identification\"\x13\n\x11GetProductRequest\"q\n\x12GetProductResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07product\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Product\"\x13\n\x11GetVersionRequest\"q\n\x12GetVersionResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07version\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Version\"6\n\nFlightInfo\x12\x14\n\x0ctime_boot_ms\x18\x01 \x01(\r\x12\x12\n\nflight_uid\x18\x02 \x01(\x04\"&\n\x0eIdentification\x12\x14\n\x0chardware_uid\x18\x01 \x01(\t\"[\n\x07Product\x12\x11\n\tvendor_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nproduct_id\x18\x03 \x01(\x05\x12\x14\n\x0cproduct_name\x18\x04 \x01(\t\"\xa7\x02\n\x07Version\x12\x17\n\x0f\x66light_sw_major\x18\x01 \x01(\x05\x12\x17\n\x0f\x66light_sw_minor\x18\x02 \x01(\x05\x12\x17\n\x0f\x66light_sw_patch\x18\x03 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_major\x18\x04 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_minor\x18\x05 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_patch\x18\x06 \x01(\x05\x12\x13\n\x0bos_sw_major\x18\x07 \x01(\x05\x12\x13\n\x0bos_sw_minor\x18\x08 \x01(\x05\x12\x13\n\x0bos_sw_patch\x18\t \x01(\x05\x12\x1a\n\x12\x66light_sw_git_hash\x18\n \x01(\t\x12\x16\n\x0eos_sw_git_hash\x18\x0b \x01(\t\"\xaf\x01\n\nInfoResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.info.InfoResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"Y\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\'\n#RESULT_INFORMATION_NOT_RECEIVED_YET\x10\x02\x32\xb4\x03\n\x0bInfoService\x12y\n\x14GetFlightInformation\x12,.mavsdk.rpc.info.GetFlightInformationRequest\x1a-.mavsdk.rpc.info.GetFlightInformationResponse\"\x04\x80\xb5\x18\x01\x12p\n\x11GetIdentification\x12).mavsdk.rpc.info.GetIdentificationRequest\x1a*.mavsdk.rpc.info.GetIdentificationResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetProduct\x12\".mavsdk.rpc.info.GetProductRequest\x1a#.mavsdk.rpc.info.GetProductResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetVersion\x12\".mavsdk.rpc.info.GetVersionRequest\x1a#.mavsdk.rpc.info.GetVersionResponse\"\x04\x80\xb5\x18\x01\x42\x1b\n\x0eio.mavsdk.infoB\tInfoProtob\x06proto3' + serialized_pb=b'\n\x0finfo/info.proto\x12\x0fmavsdk.rpc.info\x1a\x14mavsdk_options.proto\"\x1d\n\x1bGetFlightInformationRequest\"\x82\x01\n\x1cGetFlightInformationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x30\n\x0b\x66light_info\x18\x02 \x01(\x0b\x32\x1b.mavsdk.rpc.info.FlightInfo\"\x1a\n\x18GetIdentificationRequest\"\x86\x01\n\x19GetIdentificationResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x37\n\x0eidentification\x18\x02 \x01(\x0b\x32\x1f.mavsdk.rpc.info.Identification\"\x13\n\x11GetProductRequest\"q\n\x12GetProductResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07product\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Product\"\x13\n\x11GetVersionRequest\"q\n\x12GetVersionResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12)\n\x07version\x18\x02 \x01(\x0b\x32\x18.mavsdk.rpc.info.Version\"\x17\n\x15GetSpeedFactorRequest\"`\n\x16GetSpeedFactorResponse\x12\x30\n\x0binfo_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.info.InfoResult\x12\x14\n\x0cspeed_factor\x18\x02 \x01(\x01\"6\n\nFlightInfo\x12\x14\n\x0ctime_boot_ms\x18\x01 \x01(\r\x12\x12\n\nflight_uid\x18\x02 \x01(\x04\"&\n\x0eIdentification\x12\x14\n\x0chardware_uid\x18\x01 \x01(\t\"[\n\x07Product\x12\x11\n\tvendor_id\x18\x01 \x01(\x05\x12\x13\n\x0bvendor_name\x18\x02 \x01(\t\x12\x12\n\nproduct_id\x18\x03 \x01(\x05\x12\x14\n\x0cproduct_name\x18\x04 \x01(\t\"\xa7\x02\n\x07Version\x12\x17\n\x0f\x66light_sw_major\x18\x01 \x01(\x05\x12\x17\n\x0f\x66light_sw_minor\x18\x02 \x01(\x05\x12\x17\n\x0f\x66light_sw_patch\x18\x03 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_major\x18\x04 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_minor\x18\x05 \x01(\x05\x12\x1e\n\x16\x66light_sw_vendor_patch\x18\x06 \x01(\x05\x12\x13\n\x0bos_sw_major\x18\x07 \x01(\x05\x12\x13\n\x0bos_sw_minor\x18\x08 \x01(\x05\x12\x13\n\x0bos_sw_patch\x18\t \x01(\x05\x12\x1a\n\x12\x66light_sw_git_hash\x18\n \x01(\t\x12\x16\n\x0eos_sw_git_hash\x18\x0b \x01(\t\"\xaf\x01\n\nInfoResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.info.InfoResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"Y\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\'\n#RESULT_INFORMATION_NOT_RECEIVED_YET\x10\x02\x32\x9d\x04\n\x0bInfoService\x12y\n\x14GetFlightInformation\x12,.mavsdk.rpc.info.GetFlightInformationRequest\x1a-.mavsdk.rpc.info.GetFlightInformationResponse\"\x04\x80\xb5\x18\x01\x12p\n\x11GetIdentification\x12).mavsdk.rpc.info.GetIdentificationRequest\x1a*.mavsdk.rpc.info.GetIdentificationResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetProduct\x12\".mavsdk.rpc.info.GetProductRequest\x1a#.mavsdk.rpc.info.GetProductResponse\"\x04\x80\xb5\x18\x01\x12[\n\nGetVersion\x12\".mavsdk.rpc.info.GetVersionRequest\x1a#.mavsdk.rpc.info.GetVersionResponse\"\x04\x80\xb5\x18\x01\x12g\n\x0eGetSpeedFactor\x12&.mavsdk.rpc.info.GetSpeedFactorRequest\x1a\'.mavsdk.rpc.info.GetSpeedFactorResponse\"\x04\x80\xb5\x18\x01\x42\x1b\n\x0eio.mavsdk.infoB\tInfoProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -46,8 +46,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=1233, - serialized_end=1322, + serialized_start=1356, + serialized_end=1445, ) _sym_db.RegisterEnumDescriptor(_INFORESULT_RESULT) @@ -300,6 +300,68 @@ ) +_GETSPEEDFACTORREQUEST = _descriptor.Descriptor( + name='GetSpeedFactorRequest', + full_name='mavsdk.rpc.info.GetSpeedFactorRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=659, + serialized_end=682, +) + + +_GETSPEEDFACTORRESPONSE = _descriptor.Descriptor( + name='GetSpeedFactorResponse', + full_name='mavsdk.rpc.info.GetSpeedFactorResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='info_result', full_name='mavsdk.rpc.info.GetSpeedFactorResponse.info_result', index=0, + number=1, type=11, cpp_type=10, label=1, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='speed_factor', full_name='mavsdk.rpc.info.GetSpeedFactorResponse.speed_factor', index=1, + number=2, type=1, cpp_type=5, 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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=684, + serialized_end=780, +) + + _FLIGHTINFO = _descriptor.Descriptor( name='FlightInfo', full_name='mavsdk.rpc.info.FlightInfo', @@ -333,8 +395,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=659, - serialized_end=713, + serialized_start=782, + serialized_end=836, ) @@ -364,8 +426,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=715, - serialized_end=753, + serialized_start=838, + serialized_end=876, ) @@ -416,8 +478,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=755, - serialized_end=846, + serialized_start=878, + serialized_end=969, ) @@ -517,8 +579,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=849, - serialized_end=1144, + serialized_start=972, + serialized_end=1267, ) @@ -556,8 +618,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=1147, - serialized_end=1322, + serialized_start=1270, + serialized_end=1445, ) _GETFLIGHTINFORMATIONRESPONSE.fields_by_name['info_result'].message_type = _INFORESULT @@ -568,6 +630,7 @@ _GETPRODUCTRESPONSE.fields_by_name['product'].message_type = _PRODUCT _GETVERSIONRESPONSE.fields_by_name['info_result'].message_type = _INFORESULT _GETVERSIONRESPONSE.fields_by_name['version'].message_type = _VERSION +_GETSPEEDFACTORRESPONSE.fields_by_name['info_result'].message_type = _INFORESULT _INFORESULT.fields_by_name['result'].enum_type = _INFORESULT_RESULT _INFORESULT_RESULT.containing_type = _INFORESULT DESCRIPTOR.message_types_by_name['GetFlightInformationRequest'] = _GETFLIGHTINFORMATIONREQUEST @@ -578,6 +641,8 @@ DESCRIPTOR.message_types_by_name['GetProductResponse'] = _GETPRODUCTRESPONSE DESCRIPTOR.message_types_by_name['GetVersionRequest'] = _GETVERSIONREQUEST DESCRIPTOR.message_types_by_name['GetVersionResponse'] = _GETVERSIONRESPONSE +DESCRIPTOR.message_types_by_name['GetSpeedFactorRequest'] = _GETSPEEDFACTORREQUEST +DESCRIPTOR.message_types_by_name['GetSpeedFactorResponse'] = _GETSPEEDFACTORRESPONSE DESCRIPTOR.message_types_by_name['FlightInfo'] = _FLIGHTINFO DESCRIPTOR.message_types_by_name['Identification'] = _IDENTIFICATION DESCRIPTOR.message_types_by_name['Product'] = _PRODUCT @@ -641,6 +706,20 @@ }) _sym_db.RegisterMessage(GetVersionResponse) +GetSpeedFactorRequest = _reflection.GeneratedProtocolMessageType('GetSpeedFactorRequest', (_message.Message,), { + 'DESCRIPTOR' : _GETSPEEDFACTORREQUEST, + '__module__' : 'info.info_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.info.GetSpeedFactorRequest) + }) +_sym_db.RegisterMessage(GetSpeedFactorRequest) + +GetSpeedFactorResponse = _reflection.GeneratedProtocolMessageType('GetSpeedFactorResponse', (_message.Message,), { + 'DESCRIPTOR' : _GETSPEEDFACTORRESPONSE, + '__module__' : 'info.info_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.info.GetSpeedFactorResponse) + }) +_sym_db.RegisterMessage(GetSpeedFactorResponse) + FlightInfo = _reflection.GeneratedProtocolMessageType('FlightInfo', (_message.Message,), { 'DESCRIPTOR' : _FLIGHTINFO, '__module__' : 'info.info_pb2' @@ -685,8 +764,8 @@ file=DESCRIPTOR, index=0, serialized_options=None, - serialized_start=1325, - serialized_end=1761, + serialized_start=1448, + serialized_end=1989, methods=[ _descriptor.MethodDescriptor( name='GetFlightInformation', @@ -724,6 +803,15 @@ output_type=_GETVERSIONRESPONSE, serialized_options=b'\200\265\030\001', ), + _descriptor.MethodDescriptor( + name='GetSpeedFactor', + full_name='mavsdk.rpc.info.InfoService.GetSpeedFactor', + index=4, + containing_service=None, + input_type=_GETSPEEDFACTORREQUEST, + output_type=_GETSPEEDFACTORRESPONSE, + serialized_options=b'\200\265\030\001', + ), ]) _sym_db.RegisterServiceDescriptor(_INFOSERVICE) diff --git a/mavsdk/info_pb2_grpc.py b/mavsdk/info_pb2_grpc.py index 78b68b88..60edbd7e 100644 --- a/mavsdk/info_pb2_grpc.py +++ b/mavsdk/info_pb2_grpc.py @@ -34,6 +34,11 @@ def __init__(self, channel): request_serializer=info_dot_info__pb2.GetVersionRequest.SerializeToString, response_deserializer=info_dot_info__pb2.GetVersionResponse.FromString, ) + self.GetSpeedFactor = channel.unary_unary( + '/mavsdk.rpc.info.InfoService/GetSpeedFactor', + request_serializer=info_dot_info__pb2.GetSpeedFactorRequest.SerializeToString, + response_deserializer=info_dot_info__pb2.GetSpeedFactorResponse.FromString, + ) class InfoServiceServicer(object): @@ -68,6 +73,13 @@ def GetVersion(self, request, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def GetSpeedFactor(self, request, context): + """Get the speed factor of a simulation (with lockstep a simulation can run faster or slower than realtime). + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def add_InfoServiceServicer_to_server(servicer, server): rpc_method_handlers = { @@ -91,6 +103,11 @@ def add_InfoServiceServicer_to_server(servicer, server): request_deserializer=info_dot_info__pb2.GetVersionRequest.FromString, response_serializer=info_dot_info__pb2.GetVersionResponse.SerializeToString, ), + 'GetSpeedFactor': grpc.unary_unary_rpc_method_handler( + servicer.GetSpeedFactor, + request_deserializer=info_dot_info__pb2.GetSpeedFactorRequest.FromString, + response_serializer=info_dot_info__pb2.GetSpeedFactorResponse.SerializeToString, + ), } generic_handler = grpc.method_handlers_generic_handler( 'mavsdk.rpc.info.InfoService', rpc_method_handlers) @@ -165,3 +182,19 @@ def GetVersion(request, info_dot_info__pb2.GetVersionResponse.FromString, options, channel_credentials, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def GetSpeedFactor(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.info.InfoService/GetSpeedFactor', + info_dot_info__pb2.GetSpeedFactorRequest.SerializeToString, + info_dot_info__pb2.GetSpeedFactorResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/mavsdk/manual_control.py b/mavsdk/manual_control.py new file mode 100644 index 00000000..f65024cb --- /dev/null +++ b/mavsdk/manual_control.py @@ -0,0 +1,285 @@ +# -*- coding: utf-8 -*- +# DO NOT EDIT! This file is auto-generated from +# https://github.com/mavlink/MAVSDK-Python/tree/master/other/templates/py +from ._base import AsyncBase +from . import manual_control_pb2, manual_control_pb2_grpc +from enum import Enum + + +class ManualControlResult: + """ + Result type. + + Parameters + ---------- + result : Result + Result enum value + + result_str : std::string + Human-readable English string describing the result + + """ + + + + class Result(Enum): + """ + Possible results returned for manual control requests. + + Values + ------ + UNKNOWN + Unknown result + + SUCCESS + Request was successful + + NO_SYSTEM + No system is connected + + CONNECTION_ERROR + Connection error + + BUSY + Vehicle is busy + + COMMAND_DENIED + Command refused by vehicle + + TIMEOUT + Request timed out + + INPUT_OUT_OF_RANGE + Input out of range + + """ + + + UNKNOWN = 0 + SUCCESS = 1 + NO_SYSTEM = 2 + CONNECTION_ERROR = 3 + BUSY = 4 + COMMAND_DENIED = 5 + TIMEOUT = 6 + INPUT_OUT_OF_RANGE = 7 + + def translate_to_rpc(self): + if self == ManualControlResult.Result.UNKNOWN: + return manual_control_pb2.ManualControlResult.RESULT_UNKNOWN + if self == ManualControlResult.Result.SUCCESS: + return manual_control_pb2.ManualControlResult.RESULT_SUCCESS + if self == ManualControlResult.Result.NO_SYSTEM: + return manual_control_pb2.ManualControlResult.RESULT_NO_SYSTEM + if self == ManualControlResult.Result.CONNECTION_ERROR: + return manual_control_pb2.ManualControlResult.RESULT_CONNECTION_ERROR + if self == ManualControlResult.Result.BUSY: + return manual_control_pb2.ManualControlResult.RESULT_BUSY + if self == ManualControlResult.Result.COMMAND_DENIED: + return manual_control_pb2.ManualControlResult.RESULT_COMMAND_DENIED + if self == ManualControlResult.Result.TIMEOUT: + return manual_control_pb2.ManualControlResult.RESULT_TIMEOUT + if self == ManualControlResult.Result.INPUT_OUT_OF_RANGE: + return manual_control_pb2.ManualControlResult.RESULT_INPUT_OUT_OF_RANGE + + @staticmethod + def translate_from_rpc(rpc_enum_value): + """ Parses a gRPC response """ + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_UNKNOWN: + return ManualControlResult.Result.UNKNOWN + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_SUCCESS: + return ManualControlResult.Result.SUCCESS + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_NO_SYSTEM: + return ManualControlResult.Result.NO_SYSTEM + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_CONNECTION_ERROR: + return ManualControlResult.Result.CONNECTION_ERROR + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_BUSY: + return ManualControlResult.Result.BUSY + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_COMMAND_DENIED: + return ManualControlResult.Result.COMMAND_DENIED + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_TIMEOUT: + return ManualControlResult.Result.TIMEOUT + if rpc_enum_value == manual_control_pb2.ManualControlResult.RESULT_INPUT_OUT_OF_RANGE: + return ManualControlResult.Result.INPUT_OUT_OF_RANGE + + def __str__(self): + return self.name + + + def __init__( + self, + result, + result_str): + """ Initializes the ManualControlResult object """ + self.result = result + self.result_str = result_str + + def __equals__(self, to_compare): + """ Checks if two ManualControlResult are the same """ + try: + # Try to compare - this likely fails when it is compared to a non + # ManualControlResult object + return \ + (self.result == to_compare.result) and \ + (self.result_str == to_compare.result_str) + + except AttributeError: + return False + + def __str__(self): + """ ManualControlResult in string representation """ + struct_repr = ", ".join([ + "result: " + str(self.result), + "result_str: " + str(self.result_str) + ]) + + return f"ManualControlResult: [{struct_repr}]" + + @staticmethod + def translate_from_rpc(rpcManualControlResult): + """ Translates a gRPC struct to the SDK equivalent """ + return ManualControlResult( + + ManualControlResult.Result.translate_from_rpc(rpcManualControlResult.result), + + + rpcManualControlResult.result_str + ) + + def translate_to_rpc(self, rpcManualControlResult): + """ Translates this SDK object into its gRPC equivalent """ + + + + + rpcManualControlResult.result = self.result.translate_to_rpc() + + + + + + rpcManualControlResult.result_str = self.result_str + + + + + + +class ManualControlError(Exception): + """ Raised when a ManualControlResult is a fail code """ + + def __init__(self, result, origin, *params): + self._result = result + self._origin = origin + self._params = params + + def __str__(self): + return f"{self._result.result}: '{self._result.result_str}'; origin: {self._origin}; params: {self._params}" + + +class ManualControl(AsyncBase): + """ + Enable manual control using e.g. a joystick or gamepad. + + Generated by dcsdkgen - MAVSDK ManualControl API + """ + + # Plugin name + name = "ManualControl" + + def _setup_stub(self, channel): + """ Setups the api stub """ + self._stub = manual_control_pb2_grpc.ManualControlServiceStub(channel) + + + def _extract_result(self, response): + """ Returns the response status and description """ + return ManualControlResult.translate_from_rpc(response.manual_control_result) + + + async def start_position_control(self): + """ + Start position control using e.g. joystick input. + + Requires manual control input to be sent regularly already. + Requires a valid position using e.g. GPS, external vision, or optical flow. + + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. + """ + + request = manual_control_pb2.StartPositionControlRequest() + response = await self._stub.StartPositionControl(request) + + + result = self._extract_result(response) + + if result.result is not ManualControlResult.Result.SUCCESS: + raise ManualControlError(result, "start_position_control()") + + + async def start_altitude_control(self): + """ + Start altitude control + + Requires manual control input to be sent regularly already. + Does not require a valid position e.g. GPS. + + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. + """ + + request = manual_control_pb2.StartAltitudeControlRequest() + response = await self._stub.StartAltitudeControl(request) + + + result = self._extract_result(response) + + if result.result is not ManualControlResult.Result.SUCCESS: + raise ManualControlError(result, "start_altitude_control()") + + + async def set_manual_control_input(self, x, y, z, r): + """ + Set manual control input + + The manual control input needs to be sent at a rate high enough to prevent + triggering of RC loss, a good minimum rate is 10 Hz. + + Parameters + ---------- + x : float + value between -1. to 1. negative -> backwards, positive -> forwards + + y : float + value between -1. to 1. negative -> left, positive -> right + + z : float + value between -1. to 1. negative -> down, positive -> up (usually for now, for multicopter 0 to 1 is expected) + + r : float + value between -1. to 1. negative -> turn anti-clockwise (towards the left), positive -> turn clockwise (towards the right) + + Raises + ------ + ManualControlError + If the request fails. The error contains the reason for the failure. + """ + + request = manual_control_pb2.SetManualControlInputRequest() + request.x = x + request.y = y + request.z = z + request.r = r + response = await self._stub.SetManualControlInput(request) + + + result = self._extract_result(response) + + if result.result is not ManualControlResult.Result.SUCCESS: + raise ManualControlError(result, "set_manual_control_input()", x, y, z, r) + \ No newline at end of file diff --git a/mavsdk/manual_control_pb2.py b/mavsdk/manual_control_pb2.py new file mode 100644 index 00000000..a6804409 --- /dev/null +++ b/mavsdk/manual_control_pb2.py @@ -0,0 +1,413 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: manual_control/manual_control.proto + +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + +from . import mavsdk_options_pb2 as mavsdk__options__pb2 + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='manual_control/manual_control.proto', + package='mavsdk.rpc.manual_control', + syntax='proto3', + serialized_options=b'\n\030io.mavsdk.manual_controlB\022ManualControlProto', + serialized_pb=b'\n#manual_control/manual_control.proto\x12\x19mavsdk.rpc.manual_control\x1a\x14mavsdk_options.proto\"\x1d\n\x1bStartPositionControlRequest\"m\n\x1cStartPositionControlResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"\x1d\n\x1bStartAltitudeControlRequest\"m\n\x1cStartAltitudeControlResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"J\n\x1cSetManualControlInputRequest\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01r\x18\x04 \x01(\x02\"n\n\x1dSetManualControlInputResponse\x12M\n\x15manual_control_result\x18\x01 \x01(\x0b\x32..mavsdk.rpc.manual_control.ManualControlResult\"\xb5\x02\n\x13ManualControlResult\x12\x45\n\x06result\x18\x01 \x01(\x0e\x32\x35.mavsdk.rpc.manual_control.ManualControlResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"\xc2\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\x12\x1d\n\x19RESULT_INPUT_OUT_OF_RANGE\x10\x07\x32\xc1\x03\n\x14ManualControlService\x12\x89\x01\n\x14StartPositionControl\x12\x36.mavsdk.rpc.manual_control.StartPositionControlRequest\x1a\x37.mavsdk.rpc.manual_control.StartPositionControlResponse\"\x00\x12\x89\x01\n\x14StartAltitudeControl\x12\x36.mavsdk.rpc.manual_control.StartAltitudeControlRequest\x1a\x37.mavsdk.rpc.manual_control.StartAltitudeControlResponse\"\x00\x12\x90\x01\n\x15SetManualControlInput\x12\x37.mavsdk.rpc.manual_control.SetManualControlInputRequest\x1a\x38.mavsdk.rpc.manual_control.SetManualControlInputResponse\"\x04\x80\xb5\x18\x01\x42.\n\x18io.mavsdk.manual_controlB\x12ManualControlProtob\x06proto3' + , + dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) + + + +_MANUALCONTROLRESULT_RESULT = _descriptor.EnumDescriptor( + name='Result', + full_name='mavsdk.rpc.manual_control.ManualControlResult.Result', + filename=None, + file=DESCRIPTOR, + values=[ + _descriptor.EnumValueDescriptor( + name='RESULT_UNKNOWN', index=0, number=0, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_SUCCESS', index=1, number=1, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_NO_SYSTEM', index=2, number=2, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_CONNECTION_ERROR', index=3, number=3, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_BUSY', index=4, number=4, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_COMMAND_DENIED', index=5, number=5, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_TIMEOUT', index=6, number=6, + serialized_options=None, + type=None), + _descriptor.EnumValueDescriptor( + name='RESULT_INPUT_OUT_OF_RANGE', index=7, number=7, + serialized_options=None, + type=None), + ], + containing_type=None, + serialized_options=None, + serialized_start=676, + serialized_end=870, +) +_sym_db.RegisterEnumDescriptor(_MANUALCONTROLRESULT_RESULT) + + +_STARTPOSITIONCONTROLREQUEST = _descriptor.Descriptor( + name='StartPositionControlRequest', + full_name='mavsdk.rpc.manual_control.StartPositionControlRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=88, + serialized_end=117, +) + + +_STARTPOSITIONCONTROLRESPONSE = _descriptor.Descriptor( + name='StartPositionControlResponse', + full_name='mavsdk.rpc.manual_control.StartPositionControlResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='manual_control_result', full_name='mavsdk.rpc.manual_control.StartPositionControlResponse.manual_control_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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=119, + serialized_end=228, +) + + +_STARTALTITUDECONTROLREQUEST = _descriptor.Descriptor( + name='StartAltitudeControlRequest', + full_name='mavsdk.rpc.manual_control.StartAltitudeControlRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=230, + serialized_end=259, +) + + +_STARTALTITUDECONTROLRESPONSE = _descriptor.Descriptor( + name='StartAltitudeControlResponse', + full_name='mavsdk.rpc.manual_control.StartAltitudeControlResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='manual_control_result', full_name='mavsdk.rpc.manual_control.StartAltitudeControlResponse.manual_control_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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=261, + serialized_end=370, +) + + +_SETMANUALCONTROLINPUTREQUEST = _descriptor.Descriptor( + name='SetManualControlInputRequest', + full_name='mavsdk.rpc.manual_control.SetManualControlInputRequest', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='mavsdk.rpc.manual_control.SetManualControlInputRequest.x', 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), + _descriptor.FieldDescriptor( + name='y', full_name='mavsdk.rpc.manual_control.SetManualControlInputRequest.y', 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), + _descriptor.FieldDescriptor( + name='z', full_name='mavsdk.rpc.manual_control.SetManualControlInputRequest.z', index=2, + number=3, 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), + _descriptor.FieldDescriptor( + name='r', full_name='mavsdk.rpc.manual_control.SetManualControlInputRequest.r', index=3, + number=4, 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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=372, + serialized_end=446, +) + + +_SETMANUALCONTROLINPUTRESPONSE = _descriptor.Descriptor( + name='SetManualControlInputResponse', + full_name='mavsdk.rpc.manual_control.SetManualControlInputResponse', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='manual_control_result', full_name='mavsdk.rpc.manual_control.SetManualControlInputResponse.manual_control_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), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=448, + serialized_end=558, +) + + +_MANUALCONTROLRESULT = _descriptor.Descriptor( + name='ManualControlResult', + full_name='mavsdk.rpc.manual_control.ManualControlResult', + filename=None, + file=DESCRIPTOR, + containing_type=None, + fields=[ + _descriptor.FieldDescriptor( + name='result', full_name='mavsdk.rpc.manual_control.ManualControlResult.result', 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), + _descriptor.FieldDescriptor( + name='result_str', full_name='mavsdk.rpc.manual_control.ManualControlResult.result_str', index=1, + number=2, type=9, cpp_type=9, label=1, + has_default_value=False, default_value=b"".decode('utf-8'), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + _MANUALCONTROLRESULT_RESULT, + ], + serialized_options=None, + is_extendable=False, + syntax='proto3', + extension_ranges=[], + oneofs=[ + ], + serialized_start=561, + serialized_end=870, +) + +_STARTPOSITIONCONTROLRESPONSE.fields_by_name['manual_control_result'].message_type = _MANUALCONTROLRESULT +_STARTALTITUDECONTROLRESPONSE.fields_by_name['manual_control_result'].message_type = _MANUALCONTROLRESULT +_SETMANUALCONTROLINPUTRESPONSE.fields_by_name['manual_control_result'].message_type = _MANUALCONTROLRESULT +_MANUALCONTROLRESULT.fields_by_name['result'].enum_type = _MANUALCONTROLRESULT_RESULT +_MANUALCONTROLRESULT_RESULT.containing_type = _MANUALCONTROLRESULT +DESCRIPTOR.message_types_by_name['StartPositionControlRequest'] = _STARTPOSITIONCONTROLREQUEST +DESCRIPTOR.message_types_by_name['StartPositionControlResponse'] = _STARTPOSITIONCONTROLRESPONSE +DESCRIPTOR.message_types_by_name['StartAltitudeControlRequest'] = _STARTALTITUDECONTROLREQUEST +DESCRIPTOR.message_types_by_name['StartAltitudeControlResponse'] = _STARTALTITUDECONTROLRESPONSE +DESCRIPTOR.message_types_by_name['SetManualControlInputRequest'] = _SETMANUALCONTROLINPUTREQUEST +DESCRIPTOR.message_types_by_name['SetManualControlInputResponse'] = _SETMANUALCONTROLINPUTRESPONSE +DESCRIPTOR.message_types_by_name['ManualControlResult'] = _MANUALCONTROLRESULT +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +StartPositionControlRequest = _reflection.GeneratedProtocolMessageType('StartPositionControlRequest', (_message.Message,), { + 'DESCRIPTOR' : _STARTPOSITIONCONTROLREQUEST, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.StartPositionControlRequest) + }) +_sym_db.RegisterMessage(StartPositionControlRequest) + +StartPositionControlResponse = _reflection.GeneratedProtocolMessageType('StartPositionControlResponse', (_message.Message,), { + 'DESCRIPTOR' : _STARTPOSITIONCONTROLRESPONSE, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.StartPositionControlResponse) + }) +_sym_db.RegisterMessage(StartPositionControlResponse) + +StartAltitudeControlRequest = _reflection.GeneratedProtocolMessageType('StartAltitudeControlRequest', (_message.Message,), { + 'DESCRIPTOR' : _STARTALTITUDECONTROLREQUEST, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.StartAltitudeControlRequest) + }) +_sym_db.RegisterMessage(StartAltitudeControlRequest) + +StartAltitudeControlResponse = _reflection.GeneratedProtocolMessageType('StartAltitudeControlResponse', (_message.Message,), { + 'DESCRIPTOR' : _STARTALTITUDECONTROLRESPONSE, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.StartAltitudeControlResponse) + }) +_sym_db.RegisterMessage(StartAltitudeControlResponse) + +SetManualControlInputRequest = _reflection.GeneratedProtocolMessageType('SetManualControlInputRequest', (_message.Message,), { + 'DESCRIPTOR' : _SETMANUALCONTROLINPUTREQUEST, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.SetManualControlInputRequest) + }) +_sym_db.RegisterMessage(SetManualControlInputRequest) + +SetManualControlInputResponse = _reflection.GeneratedProtocolMessageType('SetManualControlInputResponse', (_message.Message,), { + 'DESCRIPTOR' : _SETMANUALCONTROLINPUTRESPONSE, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.SetManualControlInputResponse) + }) +_sym_db.RegisterMessage(SetManualControlInputResponse) + +ManualControlResult = _reflection.GeneratedProtocolMessageType('ManualControlResult', (_message.Message,), { + 'DESCRIPTOR' : _MANUALCONTROLRESULT, + '__module__' : 'manual_control.manual_control_pb2' + # @@protoc_insertion_point(class_scope:mavsdk.rpc.manual_control.ManualControlResult) + }) +_sym_db.RegisterMessage(ManualControlResult) + + +DESCRIPTOR._options = None + +_MANUALCONTROLSERVICE = _descriptor.ServiceDescriptor( + name='ManualControlService', + full_name='mavsdk.rpc.manual_control.ManualControlService', + file=DESCRIPTOR, + index=0, + serialized_options=None, + serialized_start=873, + serialized_end=1322, + methods=[ + _descriptor.MethodDescriptor( + name='StartPositionControl', + full_name='mavsdk.rpc.manual_control.ManualControlService.StartPositionControl', + index=0, + containing_service=None, + input_type=_STARTPOSITIONCONTROLREQUEST, + output_type=_STARTPOSITIONCONTROLRESPONSE, + serialized_options=None, + ), + _descriptor.MethodDescriptor( + name='StartAltitudeControl', + full_name='mavsdk.rpc.manual_control.ManualControlService.StartAltitudeControl', + index=1, + containing_service=None, + input_type=_STARTALTITUDECONTROLREQUEST, + output_type=_STARTALTITUDECONTROLRESPONSE, + serialized_options=None, + ), + _descriptor.MethodDescriptor( + name='SetManualControlInput', + full_name='mavsdk.rpc.manual_control.ManualControlService.SetManualControlInput', + index=2, + containing_service=None, + input_type=_SETMANUALCONTROLINPUTREQUEST, + output_type=_SETMANUALCONTROLINPUTRESPONSE, + serialized_options=b'\200\265\030\001', + ), +]) +_sym_db.RegisterServiceDescriptor(_MANUALCONTROLSERVICE) + +DESCRIPTOR.services_by_name['ManualControlService'] = _MANUALCONTROLSERVICE + +# @@protoc_insertion_point(module_scope) diff --git a/mavsdk/manual_control_pb2_grpc.py b/mavsdk/manual_control_pb2_grpc.py new file mode 100644 index 00000000..241b8ed1 --- /dev/null +++ b/mavsdk/manual_control_pb2_grpc.py @@ -0,0 +1,146 @@ +# Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! +import grpc + +from . import manual_control_pb2 as manual__control_dot_manual__control__pb2 + + +class ManualControlServiceStub(object): + """Enable manual control using e.g. a joystick or gamepad. + """ + + def __init__(self, channel): + """Constructor. + + Args: + channel: A grpc.Channel. + """ + self.StartPositionControl = channel.unary_unary( + '/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl', + request_serializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.FromString, + ) + self.StartAltitudeControl = channel.unary_unary( + '/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl', + request_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.FromString, + ) + self.SetManualControlInput = channel.unary_unary( + '/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput', + request_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.SerializeToString, + response_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.FromString, + ) + + +class ManualControlServiceServicer(object): + """Enable manual control using e.g. a joystick or gamepad. + """ + + def StartPositionControl(self, request, context): + """ + Start position control using e.g. joystick input. + + Requires manual control input to be sent regularly already. + Requires a valid position using e.g. GPS, external vision, or optical flow. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def StartAltitudeControl(self, request, context): + """ + Start altitude control + + Requires manual control input to be sent regularly already. + Does not require a valid position e.g. GPS. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + def SetManualControlInput(self, request, context): + """ + Set manual control input + + The manual control input needs to be sent at a rate high enough to prevent + triggering of RC loss, a good minimum rate is 10 Hz. + """ + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + +def add_ManualControlServiceServicer_to_server(servicer, server): + rpc_method_handlers = { + 'StartPositionControl': grpc.unary_unary_rpc_method_handler( + servicer.StartPositionControl, + request_deserializer=manual__control_dot_manual__control__pb2.StartPositionControlRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.StartPositionControlResponse.SerializeToString, + ), + 'StartAltitudeControl': grpc.unary_unary_rpc_method_handler( + servicer.StartAltitudeControl, + request_deserializer=manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.SerializeToString, + ), + 'SetManualControlInput': grpc.unary_unary_rpc_method_handler( + servicer.SetManualControlInput, + request_deserializer=manual__control_dot_manual__control__pb2.SetManualControlInputRequest.FromString, + response_serializer=manual__control_dot_manual__control__pb2.SetManualControlInputResponse.SerializeToString, + ), + } + generic_handler = grpc.method_handlers_generic_handler( + 'mavsdk.rpc.manual_control.ManualControlService', rpc_method_handlers) + server.add_generic_rpc_handlers((generic_handler,)) + + + # This class is part of an EXPERIMENTAL API. +class ManualControlService(object): + """Enable manual control using e.g. a joystick or gamepad. + """ + + @staticmethod + def StartPositionControl(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.manual_control.ManualControlService/StartPositionControl', + manual__control_dot_manual__control__pb2.StartPositionControlRequest.SerializeToString, + manual__control_dot_manual__control__pb2.StartPositionControlResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def StartAltitudeControl(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.manual_control.ManualControlService/StartAltitudeControl', + manual__control_dot_manual__control__pb2.StartAltitudeControlRequest.SerializeToString, + manual__control_dot_manual__control__pb2.StartAltitudeControlResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def SetManualControlInput(request, + target, + options=(), + channel_credentials=None, + call_credentials=None, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.manual_control.ManualControlService/SetManualControlInput', + manual__control_dot_manual__control__pb2.SetManualControlInputRequest.SerializeToString, + manual__control_dot_manual__control__pb2.SetManualControlInputResponse.FromString, + options, channel_credentials, + call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/mavsdk/offboard.py b/mavsdk/offboard.py index f1e0db7e..63ce7f56 100644 --- a/mavsdk/offboard.py +++ b/mavsdk/offboard.py @@ -1058,7 +1058,7 @@ async def set_position_ned(self, position_ned_yaw): async def set_velocity_body(self, velocity_body_yawspeed): """ - Set the velocity in body coordinates and yaw angular rate. + Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. Parameters ---------- @@ -1087,7 +1087,7 @@ async def set_velocity_body(self, velocity_body_yawspeed): async def set_velocity_ned(self, velocity_ned_yaw): """ - Set the velocity in NED coordinates and yaw. + Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. Parameters ---------- diff --git a/mavsdk/offboard_pb2_grpc.py b/mavsdk/offboard_pb2_grpc.py index ad4f42f6..d58f680a 100644 --- a/mavsdk/offboard_pb2_grpc.py +++ b/mavsdk/offboard_pb2_grpc.py @@ -147,7 +147,7 @@ def SetPositionNed(self, request, context): def SetVelocityBody(self, request, context): """ - Set the velocity in body coordinates and yaw angular rate. + Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) context.set_details('Method not implemented!') @@ -155,7 +155,7 @@ def SetVelocityBody(self, request, context): def SetVelocityNed(self, request, context): """ - Set the velocity in NED coordinates and yaw. + Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft. """ context.set_code(grpc.StatusCode.UNIMPLEMENTED) context.set_details('Method not implemented!') diff --git a/mavsdk/source/plugins/failure.rst b/mavsdk/source/plugins/failure.rst new file mode 100644 index 00000000..c72ed4c2 --- /dev/null +++ b/mavsdk/source/plugins/failure.rst @@ -0,0 +1,8 @@ +Failure +==== + +.. automodule:: mavsdk.failure + :members: + :undoc-members: + :show-inheritance: + :exclude-members: translate_from_rpc, translate_to_rpc \ No newline at end of file diff --git a/mavsdk/source/plugins/index.rst b/mavsdk/source/plugins/index.rst index 232ff6bf..f9837fdc 100644 --- a/mavsdk/source/plugins/index.rst +++ b/mavsdk/source/plugins/index.rst @@ -22,3 +22,5 @@ Plugins shell telemetry tune + failure + manual_control diff --git a/mavsdk/source/plugins/manual_control.rst b/mavsdk/source/plugins/manual_control.rst new file mode 100644 index 00000000..bf3f498b --- /dev/null +++ b/mavsdk/source/plugins/manual_control.rst @@ -0,0 +1,8 @@ +ManualControl +==== + +.. automodule:: mavsdk.manual_control + :members: + :undoc-members: + :show-inheritance: + :exclude-members: translate_from_rpc, translate_to_rpc \ No newline at end of file diff --git a/mavsdk/tune.py b/mavsdk/tune.py index dfaa9d3c..f84a55fc 100644 --- a/mavsdk/tune.py +++ b/mavsdk/tune.py @@ -440,13 +440,13 @@ def _extract_result(self, response): return TuneResult.translate_from_rpc(response.tune_result) - async def play_tune(self, description): + async def play_tune(self, tune_description): """ Send a tune to be played by the system. Parameters ---------- - description : TuneDescription + tune_description : TuneDescription The tune to be played Raises @@ -457,7 +457,7 @@ async def play_tune(self, description): request = tune_pb2.PlayTuneRequest() - description.translate_to_rpc(request.description) + tune_description.translate_to_rpc(request.tune_description) response = await self._stub.PlayTune(request) @@ -466,5 +466,5 @@ async def play_tune(self, description): result = self._extract_result(response) if result.result is not TuneResult.Result.SUCCESS: - raise TuneError(result, "play_tune()", description) + raise TuneError(result, "play_tune()", tune_description) \ No newline at end of file diff --git a/mavsdk/tune_pb2.py b/mavsdk/tune_pb2.py index fc66aa73..304ecbf7 100644 --- a/mavsdk/tune_pb2.py +++ b/mavsdk/tune_pb2.py @@ -20,7 +20,7 @@ package='mavsdk.rpc.tune', syntax='proto3', serialized_options=b'\n\016io.mavsdk.tuneB\tTuneProto', - serialized_pb=b'\n\x0ftune/tune.proto\x12\x0fmavsdk.rpc.tune\x1a\x14mavsdk_options.proto\"H\n\x0fPlayTuneRequest\x12\x35\n\x0b\x64\x65scription\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.tune.TuneDescription\"D\n\x10PlayTuneResponse\x12\x30\n\x0btune_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.tune.TuneResult\"U\n\x0fTuneDescription\x12\x33\n\rsong_elements\x18\x01 \x03(\x0e\x32\x1c.mavsdk.rpc.tune.SongElement\x12\r\n\x05tempo\x18\x02 \x01(\x05\"\xcc\x01\n\nTuneResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.tune.TuneResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"v\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x18\n\x14RESULT_INVALID_TEMPO\x10\x02\x12\x18\n\x14RESULT_TUNE_TOO_LONG\x10\x03\x12\x10\n\x0cRESULT_ERROR\x10\x04*\xd1\x04\n\x0bSongElement\x12\x1d\n\x19SONG_ELEMENT_STYLE_LEGATO\x10\x00\x12\x1d\n\x19SONG_ELEMENT_STYLE_NORMAL\x10\x01\x12\x1f\n\x1bSONG_ELEMENT_STYLE_STACCATO\x10\x02\x12\x1b\n\x17SONG_ELEMENT_DURATION_1\x10\x03\x12\x1b\n\x17SONG_ELEMENT_DURATION_2\x10\x04\x12\x1b\n\x17SONG_ELEMENT_DURATION_4\x10\x05\x12\x1b\n\x17SONG_ELEMENT_DURATION_8\x10\x06\x12\x1c\n\x18SONG_ELEMENT_DURATION_16\x10\x07\x12\x1c\n\x18SONG_ELEMENT_DURATION_32\x10\x08\x12\x17\n\x13SONG_ELEMENT_NOTE_A\x10\t\x12\x17\n\x13SONG_ELEMENT_NOTE_B\x10\n\x12\x17\n\x13SONG_ELEMENT_NOTE_C\x10\x0b\x12\x17\n\x13SONG_ELEMENT_NOTE_D\x10\x0c\x12\x17\n\x13SONG_ELEMENT_NOTE_E\x10\r\x12\x17\n\x13SONG_ELEMENT_NOTE_F\x10\x0e\x12\x17\n\x13SONG_ELEMENT_NOTE_G\x10\x0f\x12\x1b\n\x17SONG_ELEMENT_NOTE_PAUSE\x10\x10\x12\x16\n\x12SONG_ELEMENT_SHARP\x10\x11\x12\x15\n\x11SONG_ELEMENT_FLAT\x10\x12\x12\x1a\n\x16SONG_ELEMENT_OCTAVE_UP\x10\x13\x12\x1c\n\x18SONG_ELEMENT_OCTAVE_DOWN\x10\x14\x32`\n\x0bTuneService\x12Q\n\x08PlayTune\x12 .mavsdk.rpc.tune.PlayTuneRequest\x1a!.mavsdk.rpc.tune.PlayTuneResponse\"\x00\x42\x1b\n\x0eio.mavsdk.tuneB\tTuneProtob\x06proto3' + serialized_pb=b'\n\x0ftune/tune.proto\x12\x0fmavsdk.rpc.tune\x1a\x14mavsdk_options.proto\"M\n\x0fPlayTuneRequest\x12:\n\x10tune_description\x18\x01 \x01(\x0b\x32 .mavsdk.rpc.tune.TuneDescription\"D\n\x10PlayTuneResponse\x12\x30\n\x0btune_result\x18\x01 \x01(\x0b\x32\x1b.mavsdk.rpc.tune.TuneResult\"U\n\x0fTuneDescription\x12\x33\n\rsong_elements\x18\x01 \x03(\x0e\x32\x1c.mavsdk.rpc.tune.SongElement\x12\r\n\x05tempo\x18\x02 \x01(\x05\"\xcc\x01\n\nTuneResult\x12\x32\n\x06result\x18\x01 \x01(\x0e\x32\".mavsdk.rpc.tune.TuneResult.Result\x12\x12\n\nresult_str\x18\x02 \x01(\t\"v\n\x06Result\x12\x12\n\x0eRESULT_UNKNOWN\x10\x00\x12\x12\n\x0eRESULT_SUCCESS\x10\x01\x12\x18\n\x14RESULT_INVALID_TEMPO\x10\x02\x12\x18\n\x14RESULT_TUNE_TOO_LONG\x10\x03\x12\x10\n\x0cRESULT_ERROR\x10\x04*\xd1\x04\n\x0bSongElement\x12\x1d\n\x19SONG_ELEMENT_STYLE_LEGATO\x10\x00\x12\x1d\n\x19SONG_ELEMENT_STYLE_NORMAL\x10\x01\x12\x1f\n\x1bSONG_ELEMENT_STYLE_STACCATO\x10\x02\x12\x1b\n\x17SONG_ELEMENT_DURATION_1\x10\x03\x12\x1b\n\x17SONG_ELEMENT_DURATION_2\x10\x04\x12\x1b\n\x17SONG_ELEMENT_DURATION_4\x10\x05\x12\x1b\n\x17SONG_ELEMENT_DURATION_8\x10\x06\x12\x1c\n\x18SONG_ELEMENT_DURATION_16\x10\x07\x12\x1c\n\x18SONG_ELEMENT_DURATION_32\x10\x08\x12\x17\n\x13SONG_ELEMENT_NOTE_A\x10\t\x12\x17\n\x13SONG_ELEMENT_NOTE_B\x10\n\x12\x17\n\x13SONG_ELEMENT_NOTE_C\x10\x0b\x12\x17\n\x13SONG_ELEMENT_NOTE_D\x10\x0c\x12\x17\n\x13SONG_ELEMENT_NOTE_E\x10\r\x12\x17\n\x13SONG_ELEMENT_NOTE_F\x10\x0e\x12\x17\n\x13SONG_ELEMENT_NOTE_G\x10\x0f\x12\x1b\n\x17SONG_ELEMENT_NOTE_PAUSE\x10\x10\x12\x16\n\x12SONG_ELEMENT_SHARP\x10\x11\x12\x15\n\x11SONG_ELEMENT_FLAT\x10\x12\x12\x1a\n\x16SONG_ELEMENT_OCTAVE_UP\x10\x13\x12\x1c\n\x18SONG_ELEMENT_OCTAVE_DOWN\x10\x14\x32`\n\x0bTuneService\x12Q\n\x08PlayTune\x12 .mavsdk.rpc.tune.PlayTuneRequest\x1a!.mavsdk.rpc.tune.PlayTuneResponse\"\x00\x42\x1b\n\x0eio.mavsdk.tuneB\tTuneProtob\x06proto3' , dependencies=[mavsdk__options__pb2.DESCRIPTOR,]) @@ -117,8 +117,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=497, - serialized_end=1090, + serialized_start=502, + serialized_end=1095, ) _sym_db.RegisterEnumDescriptor(_SONGELEMENT) @@ -175,8 +175,8 @@ ], containing_type=None, serialized_options=None, - serialized_start=376, - serialized_end=494, + serialized_start=381, + serialized_end=499, ) _sym_db.RegisterEnumDescriptor(_TUNERESULT_RESULT) @@ -189,7 +189,7 @@ containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='description', full_name='mavsdk.rpc.tune.PlayTuneRequest.description', index=0, + name='tune_description', full_name='mavsdk.rpc.tune.PlayTuneRequest.tune_description', 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, @@ -208,7 +208,7 @@ oneofs=[ ], serialized_start=58, - serialized_end=130, + serialized_end=135, ) @@ -238,8 +238,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=132, - serialized_end=200, + serialized_start=137, + serialized_end=205, ) @@ -276,8 +276,8 @@ extension_ranges=[], oneofs=[ ], - serialized_start=202, - serialized_end=287, + serialized_start=207, + serialized_end=292, ) @@ -315,11 +315,11 @@ extension_ranges=[], oneofs=[ ], - serialized_start=290, - serialized_end=494, + serialized_start=295, + serialized_end=499, ) -_PLAYTUNEREQUEST.fields_by_name['description'].message_type = _TUNEDESCRIPTION +_PLAYTUNEREQUEST.fields_by_name['tune_description'].message_type = _TUNEDESCRIPTION _PLAYTUNERESPONSE.fields_by_name['tune_result'].message_type = _TUNERESULT _TUNEDESCRIPTION.fields_by_name['song_elements'].enum_type = _SONGELEMENT _TUNERESULT.fields_by_name['result'].enum_type = _TUNERESULT_RESULT @@ -368,8 +368,8 @@ file=DESCRIPTOR, index=0, serialized_options=None, - serialized_start=1092, - serialized_end=1188, + serialized_start=1097, + serialized_end=1193, methods=[ _descriptor.MethodDescriptor( name='PlayTune', diff --git a/proto b/proto index 9cd9685c..85b5f7f2 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 9cd9685ce939d8681d50fb895cff4d60fcbf1e7e +Subproject commit 85b5f7f270372b8395f86af50b608544a0cd455f