Skip to content

Commit

Permalink
Update proto and mavsdk_server to v1.2.0
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Apr 1, 2022
1 parent fae8477 commit ad21f5f
Show file tree
Hide file tree
Showing 8 changed files with 226 additions and 52 deletions.
2 changes: 1 addition & 1 deletion MAVSDK_SERVER_VERSION
Original file line number Diff line number Diff line change
@@ -1 +1 @@
v1.1.0
v1.2.0
29 changes: 29 additions & 0 deletions mavsdk/action.py
Original file line number Diff line number Diff line change
Expand Up @@ -863,4 +863,33 @@ async def set_return_to_launch_altitude(self, relative_altitude_m):

if result.result != ActionResult.Result.SUCCESS:
raise ActionError(result, "set_return_to_launch_altitude()", relative_altitude_m)


async def set_current_speed(self, speed_m_s):
"""
Set current speed.
This will set the speed during a mission, reposition, and similar.
It is ephemeral, so not stored on the drone and does not survive a reboot.
Parameters
----------
speed_m_s : float
Speed in meters/second
Raises
------
ActionError
If the request fails. The error contains the reason for the failure.
"""

request = action_pb2.SetCurrentSpeedRequest()
request.speed_m_s = speed_m_s
response = await self._stub.SetCurrentSpeed(request)


result = self._extract_result(response)

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

38 changes: 29 additions & 9 deletions mavsdk/action_pb2.py

Large diffs are not rendered by default.

38 changes: 38 additions & 0 deletions mavsdk/action_pb2_grpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,11 @@ def __init__(self, channel):
request_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.SerializeToString,
response_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString,
)
self.SetCurrentSpeed = channel.unary_unary(
'/mavsdk.rpc.action.ActionService/SetCurrentSpeed',
request_serializer=action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString,
response_deserializer=action_dot_action__pb2.SetCurrentSpeedResponse.FromString,
)


class ActionServiceServicer(object):
Expand Down Expand Up @@ -343,6 +348,17 @@ def SetReturnToLaunchAltitude(self, request, context):
context.set_details('Method not implemented!')
raise NotImplementedError('Method not implemented!')

def SetCurrentSpeed(self, request, context):
"""
Set current speed.
This will set the speed during a mission, reposition, and similar.
It is ephemeral, so not stored on the drone and does not survive a reboot.
"""
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 @@ -451,6 +467,11 @@ def add_ActionServiceServicer_to_server(servicer, server):
request_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.FromString,
response_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.SerializeToString,
),
'SetCurrentSpeed': grpc.unary_unary_rpc_method_handler(
servicer.SetCurrentSpeed,
request_deserializer=action_dot_action__pb2.SetCurrentSpeedRequest.FromString,
response_serializer=action_dot_action__pb2.SetCurrentSpeedResponse.SerializeToString,
),
}
generic_handler = grpc.method_handlers_generic_handler(
'mavsdk.rpc.action.ActionService', rpc_method_handlers)
Expand Down Expand Up @@ -818,3 +839,20 @@ def SetReturnToLaunchAltitude(request,
action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString,
options, channel_credentials,
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)

@staticmethod
def SetCurrentSpeed(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/SetCurrentSpeed',
action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString,
action_dot_action__pb2.SetCurrentSpeedResponse.FromString,
options, channel_credentials,
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)
28 changes: 28 additions & 0 deletions mavsdk/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -2350,4 +2350,32 @@ async def format_storage(self):

if result.result != CameraResult.Result.SUCCESS:
raise CameraError(result, "format_storage()")


async def select_camera(self, camera_id):
"""
Select current camera .
Bind the plugin instance to a specific camera_id
Parameters
----------
camera_id : int32_t
Id of camera to be selected
Raises
------
CameraError
If the request fails. The error contains the reason for the failure.
"""

request = camera_pb2.SelectCameraRequest()
request.camera_id = camera_id
response = await self._stub.SelectCamera(request)


result = self._extract_result(response)

if result.result != CameraResult.Result.SUCCESS:
raise CameraError(result, "select_camera()", camera_id)

104 changes: 63 additions & 41 deletions mavsdk/camera_pb2.py

Large diffs are not rendered by default.

37 changes: 37 additions & 0 deletions mavsdk/camera_pb2_grpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,11 @@ def __init__(self, channel):
request_serializer=camera_dot_camera__pb2.FormatStorageRequest.SerializeToString,
response_deserializer=camera_dot_camera__pb2.FormatStorageResponse.FromString,
)
self.SelectCamera = channel.unary_unary(
'/mavsdk.rpc.camera.CameraService/SelectCamera',
request_serializer=camera_dot_camera__pb2.SelectCameraRequest.SerializeToString,
response_deserializer=camera_dot_camera__pb2.SelectCameraResponse.FromString,
)


class CameraServiceServicer(object):
Expand Down Expand Up @@ -301,6 +306,16 @@ def FormatStorage(self, request, context):
context.set_details('Method not implemented!')
raise NotImplementedError('Method not implemented!')

def SelectCamera(self, request, context):
"""
Select current camera .
Bind the plugin instance to a specific camera_id
"""
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
context.set_details('Method not implemented!')
raise NotImplementedError('Method not implemented!')


def add_CameraServiceServicer_to_server(servicer, server):
rpc_method_handlers = {
Expand Down Expand Up @@ -404,6 +419,11 @@ def add_CameraServiceServicer_to_server(servicer, server):
request_deserializer=camera_dot_camera__pb2.FormatStorageRequest.FromString,
response_serializer=camera_dot_camera__pb2.FormatStorageResponse.SerializeToString,
),
'SelectCamera': grpc.unary_unary_rpc_method_handler(
servicer.SelectCamera,
request_deserializer=camera_dot_camera__pb2.SelectCameraRequest.FromString,
response_serializer=camera_dot_camera__pb2.SelectCameraResponse.SerializeToString,
),
}
generic_handler = grpc.method_handlers_generic_handler(
'mavsdk.rpc.camera.CameraService', rpc_method_handlers)
Expand Down Expand Up @@ -761,3 +781,20 @@ def FormatStorage(request,
camera_dot_camera__pb2.FormatStorageResponse.FromString,
options, channel_credentials,
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)

@staticmethod
def SelectCamera(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.camera.CameraService/SelectCamera',
camera_dot_camera__pb2.SelectCameraRequest.SerializeToString,
camera_dot_camera__pb2.SelectCameraResponse.FromString,
options, channel_credentials,
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)
2 changes: 1 addition & 1 deletion proto
Submodule proto updated from 4446fa to 6a7059

0 comments on commit ad21f5f

Please sign in to comment.