Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion MAVSDK_SERVER_VERSION
Original file line number Diff line number Diff line change
@@ -1 +1 @@
v3.10.2
v3.15.0
110 changes: 110 additions & 0 deletions mavsdk/action.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,41 @@ def __str__(self):
return self.name


class RelayCommand(Enum):
"""
Commanded values for relays

Values
------
ON
Turn the relay off

OFF
Turn the relay on.

"""

ON = 0
OFF = 1

def translate_to_rpc(self):
if self == RelayCommand.ON:
return action_pb2.RELAY_COMMAND_ON
if self == RelayCommand.OFF:
return action_pb2.RELAY_COMMAND_OFF

@staticmethod
def translate_from_rpc(rpc_enum_value):
"""Parses a gRPC response"""
if rpc_enum_value == action_pb2.RELAY_COMMAND_ON:
return RelayCommand.ON
if rpc_enum_value == action_pb2.RELAY_COMMAND_OFF:
return RelayCommand.OFF

def __str__(self):
return self.name


class ActionResult:
"""
Result type.
Expand Down Expand Up @@ -684,6 +719,39 @@ async def set_actuator(self, index, value):
if result.result != ActionResult.Result.SUCCESS:
raise ActionError(result, "set_actuator()", index, value)

async def set_relay(self, index, setting):
"""
Send command to set the value of a relay.

The index of the relay starts at 0.
For the relay value, 1=on, 0=off, others possible depending on system hardware

Parameters
----------
index : int32_t
Index of relay (starting with 0)

setting : RelayCommand
Value to set the relay to

Raises
------
ActionError
If the request fails. The error contains the reason for the failure.
"""

request = action_pb2.SetRelayRequest()
request.index = index

request.setting = setting.translate_to_rpc()

response = await self._stub.SetRelay(request)

result = self._extract_result(response)

if result.result != ActionResult.Result.SUCCESS:
raise ActionError(result, "set_relay()", index, setting)

async def transition_to_fixedwing(self):
"""
Send command to transition the drone to fixedwing.
Expand Down Expand Up @@ -854,3 +922,45 @@ async def set_current_speed(self, speed_m_s):

if result.result != ActionResult.Result.SUCCESS:
raise ActionError(result, "set_current_speed()", speed_m_s)

async def set_gps_global_origin(
self, latitude_deg, longitude_deg, absolute_altitude_m
):
"""
Set GPS Global Origin.

Sets the GPS coordinates of the vehicle local origin (0,0,0) position.

Parameters
----------
latitude_deg : double
Latitude (in degrees)

longitude_deg : double
Longitude (in degrees)

absolute_altitude_m : float
Altitude AMSL (in meters)

Raises
------
ActionError
If the request fails. The error contains the reason for the failure.
"""

request = action_pb2.SetGpsGlobalOriginRequest()
request.latitude_deg = latitude_deg
request.longitude_deg = longitude_deg
request.absolute_altitude_m = absolute_altitude_m
response = await self._stub.SetGpsGlobalOrigin(request)

result = self._extract_result(response)

if result.result != ActionResult.Result.SUCCESS:
raise ActionError(
result,
"set_gps_global_origin()",
latitude_deg,
longitude_deg,
absolute_altitude_m,
)
90 changes: 53 additions & 37 deletions mavsdk/action_pb2.py

Large diffs are not rendered by default.

103 changes: 103 additions & 0 deletions mavsdk/action_pb2_grpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,12 @@ def __init__(self, channel):
response_deserializer=action_dot_action__pb2.SetActuatorResponse.FromString,
_registered_method=True,
)
self.SetRelay = channel.unary_unary(
"/mavsdk.rpc.action.ActionService/SetRelay",
request_serializer=action_dot_action__pb2.SetRelayRequest.SerializeToString,
response_deserializer=action_dot_action__pb2.SetRelayResponse.FromString,
_registered_method=True,
)
self.TransitionToFixedwing = channel.unary_unary(
"/mavsdk.rpc.action.ActionService/TransitionToFixedwing",
request_serializer=action_dot_action__pb2.TransitionToFixedwingRequest.SerializeToString,
Expand Down Expand Up @@ -164,6 +170,12 @@ def __init__(self, channel):
response_deserializer=action_dot_action__pb2.SetCurrentSpeedResponse.FromString,
_registered_method=True,
)
self.SetGpsGlobalOrigin = channel.unary_unary(
"/mavsdk.rpc.action.ActionService/SetGpsGlobalOrigin",
request_serializer=action_dot_action__pb2.SetGpsGlobalOriginRequest.SerializeToString,
response_deserializer=action_dot_action__pb2.SetGpsGlobalOriginResponse.FromString,
_registered_method=True,
)


class ActionServiceServicer(object):
Expand Down Expand Up @@ -329,6 +341,17 @@ def SetActuator(self, request, context):
context.set_details("Method not implemented!")
raise NotImplementedError("Method not implemented!")

def SetRelay(self, request, context):
"""
Send command to set the value of a relay.

The index of the relay starts at 0.
For the relay value, 1=on, 0=off, others possible depending on system hardware
"""
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
context.set_details("Method not implemented!")
raise NotImplementedError("Method not implemented!")

def TransitionToFixedwing(self, request, context):
"""
Send command to transition the drone to fixedwing.
Expand Down Expand Up @@ -396,6 +419,16 @@ def SetCurrentSpeed(self, request, context):
context.set_details("Method not implemented!")
raise NotImplementedError("Method not implemented!")

def SetGpsGlobalOrigin(self, request, context):
"""
Set GPS Global Origin.

Sets the GPS coordinates of the vehicle local origin (0,0,0) position.
"""
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
context.set_details("Method not implemented!")
raise NotImplementedError("Method not implemented!")


def add_ActionServiceServicer_to_server(servicer, server):
rpc_method_handlers = {
Expand Down Expand Up @@ -469,6 +502,11 @@ def add_ActionServiceServicer_to_server(servicer, server):
request_deserializer=action_dot_action__pb2.SetActuatorRequest.FromString,
response_serializer=action_dot_action__pb2.SetActuatorResponse.SerializeToString,
),
"SetRelay": grpc.unary_unary_rpc_method_handler(
servicer.SetRelay,
request_deserializer=action_dot_action__pb2.SetRelayRequest.FromString,
response_serializer=action_dot_action__pb2.SetRelayResponse.SerializeToString,
),
"TransitionToFixedwing": grpc.unary_unary_rpc_method_handler(
servicer.TransitionToFixedwing,
request_deserializer=action_dot_action__pb2.TransitionToFixedwingRequest.FromString,
Expand Down Expand Up @@ -504,6 +542,11 @@ def add_ActionServiceServicer_to_server(servicer, server):
request_deserializer=action_dot_action__pb2.SetCurrentSpeedRequest.FromString,
response_serializer=action_dot_action__pb2.SetCurrentSpeedResponse.SerializeToString,
),
"SetGpsGlobalOrigin": grpc.unary_unary_rpc_method_handler(
servicer.SetGpsGlobalOrigin,
request_deserializer=action_dot_action__pb2.SetGpsGlobalOriginRequest.FromString,
response_serializer=action_dot_action__pb2.SetGpsGlobalOriginResponse.SerializeToString,
),
}
generic_handler = grpc.method_handlers_generic_handler(
"mavsdk.rpc.action.ActionService", rpc_method_handlers
Expand Down Expand Up @@ -938,6 +981,36 @@ def SetActuator(
_registered_method=True,
)

@staticmethod
def SetRelay(
request,
target,
options=(),
channel_credentials=None,
call_credentials=None,
insecure=False,
compression=None,
wait_for_ready=None,
timeout=None,
metadata=None,
):
return grpc.experimental.unary_unary(
request,
target,
"/mavsdk.rpc.action.ActionService/SetRelay",
action_dot_action__pb2.SetRelayRequest.SerializeToString,
action_dot_action__pb2.SetRelayResponse.FromString,
options,
channel_credentials,
insecure,
call_credentials,
compression,
wait_for_ready,
timeout,
metadata,
_registered_method=True,
)

@staticmethod
def TransitionToFixedwing(
request,
Expand Down Expand Up @@ -1147,3 +1220,33 @@ def SetCurrentSpeed(
metadata,
_registered_method=True,
)

@staticmethod
def SetGpsGlobalOrigin(
request,
target,
options=(),
channel_credentials=None,
call_credentials=None,
insecure=False,
compression=None,
wait_for_ready=None,
timeout=None,
metadata=None,
):
return grpc.experimental.unary_unary(
request,
target,
"/mavsdk.rpc.action.ActionService/SetGpsGlobalOrigin",
action_dot_action__pb2.SetGpsGlobalOriginRequest.SerializeToString,
action_dot_action__pb2.SetGpsGlobalOriginResponse.FromString,
options,
channel_credentials,
insecure,
call_credentials,
compression,
wait_for_ready,
timeout,
metadata,
_registered_method=True,
)
Loading
Loading