Skip to content

Commit ad21f5f

Browse files
committed
Update proto and mavsdk_server to v1.2.0
1 parent fae8477 commit ad21f5f

File tree

8 files changed

+226
-52
lines changed

8 files changed

+226
-52
lines changed

MAVSDK_SERVER_VERSION

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
v1.1.0
1+
v1.2.0

mavsdk/action.py

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -863,4 +863,33 @@ async def set_return_to_launch_altitude(self, relative_altitude_m):
863863

864864
if result.result != ActionResult.Result.SUCCESS:
865865
raise ActionError(result, "set_return_to_launch_altitude()", relative_altitude_m)
866+
867+
868+
async def set_current_speed(self, speed_m_s):
869+
"""
870+
Set current speed.
871+
872+
This will set the speed during a mission, reposition, and similar.
873+
It is ephemeral, so not stored on the drone and does not survive a reboot.
874+
875+
Parameters
876+
----------
877+
speed_m_s : float
878+
Speed in meters/second
879+
880+
Raises
881+
------
882+
ActionError
883+
If the request fails. The error contains the reason for the failure.
884+
"""
885+
886+
request = action_pb2.SetCurrentSpeedRequest()
887+
request.speed_m_s = speed_m_s
888+
response = await self._stub.SetCurrentSpeed(request)
889+
890+
891+
result = self._extract_result(response)
892+
893+
if result.result != ActionResult.Result.SUCCESS:
894+
raise ActionError(result, "set_current_speed()", speed_m_s)
866895

mavsdk/action_pb2.py

Lines changed: 29 additions & 9 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

mavsdk/action_pb2_grpc.py

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,11 @@ def __init__(self, channel):
120120
request_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.SerializeToString,
121121
response_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString,
122122
)
123+
self.SetCurrentSpeed = channel.unary_unary(
124+
'/mavsdk.rpc.action.ActionService/SetCurrentSpeed',
125+
request_serializer=action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString,
126+
response_deserializer=action_dot_action__pb2.SetCurrentSpeedResponse.FromString,
127+
)
123128

124129

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

351+
def SetCurrentSpeed(self, request, context):
352+
"""
353+
Set current speed.
354+
355+
This will set the speed during a mission, reposition, and similar.
356+
It is ephemeral, so not stored on the drone and does not survive a reboot.
357+
"""
358+
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
359+
context.set_details('Method not implemented!')
360+
raise NotImplementedError('Method not implemented!')
361+
346362

347363
def add_ActionServiceServicer_to_server(servicer, server):
348364
rpc_method_handlers = {
@@ -451,6 +467,11 @@ def add_ActionServiceServicer_to_server(servicer, server):
451467
request_deserializer=action_dot_action__pb2.SetReturnToLaunchAltitudeRequest.FromString,
452468
response_serializer=action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.SerializeToString,
453469
),
470+
'SetCurrentSpeed': grpc.unary_unary_rpc_method_handler(
471+
servicer.SetCurrentSpeed,
472+
request_deserializer=action_dot_action__pb2.SetCurrentSpeedRequest.FromString,
473+
response_serializer=action_dot_action__pb2.SetCurrentSpeedResponse.SerializeToString,
474+
),
454475
}
455476
generic_handler = grpc.method_handlers_generic_handler(
456477
'mavsdk.rpc.action.ActionService', rpc_method_handlers)
@@ -818,3 +839,20 @@ def SetReturnToLaunchAltitude(request,
818839
action_dot_action__pb2.SetReturnToLaunchAltitudeResponse.FromString,
819840
options, channel_credentials,
820841
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)
842+
843+
@staticmethod
844+
def SetCurrentSpeed(request,
845+
target,
846+
options=(),
847+
channel_credentials=None,
848+
call_credentials=None,
849+
insecure=False,
850+
compression=None,
851+
wait_for_ready=None,
852+
timeout=None,
853+
metadata=None):
854+
return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.action.ActionService/SetCurrentSpeed',
855+
action_dot_action__pb2.SetCurrentSpeedRequest.SerializeToString,
856+
action_dot_action__pb2.SetCurrentSpeedResponse.FromString,
857+
options, channel_credentials,
858+
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)

mavsdk/camera.py

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2350,4 +2350,32 @@ async def format_storage(self):
23502350

23512351
if result.result != CameraResult.Result.SUCCESS:
23522352
raise CameraError(result, "format_storage()")
2353+
2354+
2355+
async def select_camera(self, camera_id):
2356+
"""
2357+
Select current camera .
2358+
2359+
Bind the plugin instance to a specific camera_id
2360+
2361+
Parameters
2362+
----------
2363+
camera_id : int32_t
2364+
Id of camera to be selected
2365+
2366+
Raises
2367+
------
2368+
CameraError
2369+
If the request fails. The error contains the reason for the failure.
2370+
"""
2371+
2372+
request = camera_pb2.SelectCameraRequest()
2373+
request.camera_id = camera_id
2374+
response = await self._stub.SelectCamera(request)
2375+
2376+
2377+
result = self._extract_result(response)
2378+
2379+
if result.result != CameraResult.Result.SUCCESS:
2380+
raise CameraError(result, "select_camera()", camera_id)
23532381

mavsdk/camera_pb2.py

Lines changed: 63 additions & 41 deletions
Some generated files are not rendered by default. Learn more about customizing how changed files appear on GitHub.

mavsdk/camera_pb2_grpc.py

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,11 @@ def __init__(self, channel):
122122
request_serializer=camera_dot_camera__pb2.FormatStorageRequest.SerializeToString,
123123
response_deserializer=camera_dot_camera__pb2.FormatStorageResponse.FromString,
124124
)
125+
self.SelectCamera = channel.unary_unary(
126+
'/mavsdk.rpc.camera.CameraService/SelectCamera',
127+
request_serializer=camera_dot_camera__pb2.SelectCameraRequest.SerializeToString,
128+
response_deserializer=camera_dot_camera__pb2.SelectCameraResponse.FromString,
129+
)
125130

126131

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

309+
def SelectCamera(self, request, context):
310+
"""
311+
Select current camera .
312+
313+
Bind the plugin instance to a specific camera_id
314+
"""
315+
context.set_code(grpc.StatusCode.UNIMPLEMENTED)
316+
context.set_details('Method not implemented!')
317+
raise NotImplementedError('Method not implemented!')
318+
304319

305320
def add_CameraServiceServicer_to_server(servicer, server):
306321
rpc_method_handlers = {
@@ -404,6 +419,11 @@ def add_CameraServiceServicer_to_server(servicer, server):
404419
request_deserializer=camera_dot_camera__pb2.FormatStorageRequest.FromString,
405420
response_serializer=camera_dot_camera__pb2.FormatStorageResponse.SerializeToString,
406421
),
422+
'SelectCamera': grpc.unary_unary_rpc_method_handler(
423+
servicer.SelectCamera,
424+
request_deserializer=camera_dot_camera__pb2.SelectCameraRequest.FromString,
425+
response_serializer=camera_dot_camera__pb2.SelectCameraResponse.SerializeToString,
426+
),
407427
}
408428
generic_handler = grpc.method_handlers_generic_handler(
409429
'mavsdk.rpc.camera.CameraService', rpc_method_handlers)
@@ -761,3 +781,20 @@ def FormatStorage(request,
761781
camera_dot_camera__pb2.FormatStorageResponse.FromString,
762782
options, channel_credentials,
763783
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)
784+
785+
@staticmethod
786+
def SelectCamera(request,
787+
target,
788+
options=(),
789+
channel_credentials=None,
790+
call_credentials=None,
791+
insecure=False,
792+
compression=None,
793+
wait_for_ready=None,
794+
timeout=None,
795+
metadata=None):
796+
return grpc.experimental.unary_unary(request, target, '/mavsdk.rpc.camera.CameraService/SelectCamera',
797+
camera_dot_camera__pb2.SelectCameraRequest.SerializeToString,
798+
camera_dot_camera__pb2.SelectCameraResponse.FromString,
799+
options, channel_credentials,
800+
insecure, call_credentials, compression, wait_for_ready, timeout, metadata)

proto

Submodule proto updated from 4446fa1 to 6a70598

0 commit comments

Comments
 (0)