From 9c2d2ff331da1fbcb86510e6dce6ca0497e84c30 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Sun, 15 Sep 2024 11:32:18 +1000 Subject: [PATCH] CameraProtocol: ack not needed for most requests --- ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs b/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs index e5472f09a1..a9261f8bcb 100644 --- a/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs +++ b/ExtLibs/ArduPilot/Mavlink/CameraProtocol.cs @@ -141,7 +141,8 @@ private async Task RequestCameraInformationAsync() await parent.parent.doCommandAsync( parent.sysid, parent.compid, MAVLink.MAV_CMD.REQUEST_CAMERA_INFORMATION, - 0, 0, 0, 0, 0, 0, 0 + 0, 0, 0, 0, 0, 0, 0, + false // Don't wait for response ); } @@ -150,7 +151,8 @@ await parent.parent.doCommandAsync( parent.sysid, parent.compid, MAVLink.MAV_CMD.REQUEST_MESSAGE, (float)MAVLink.MAVLINK_MSG_ID.VIDEO_STREAM_INFORMATION, - 0, 0, 0, 0, 0, 0 + 0, 0, 0, 0, 0, 0, + false // Don't wait for response ); } } @@ -207,10 +209,7 @@ public void RequestMessageIntervals(int ratehz) float interval_us = (float)(1e6 / ratehz); - if (!have_camera_information) - { - Task.Run(RequestCameraInformationAsync); - } + Task.Run(RequestCameraInformationAsync); // Request FOV status Task.Run(async () => @@ -220,7 +219,8 @@ await parent.parent.doCommandAsync( MAVLink.MAV_CMD.SET_MESSAGE_INTERVAL, (float)MAVLink.MAVLINK_MSG_ID.CAMERA_FOV_STATUS, interval_us, - 0, 0, 0, 0, 0 + 0, 0, 0, 0, 0, + false // Don't wait for response ).ConfigureAwait(false); }); @@ -234,7 +234,8 @@ await parent.parent.doCommandAsync( MAVLink.MAV_CMD.SET_MESSAGE_INTERVAL, (float)MAVLink.MAVLINK_MSG_ID.CAMERA_SETTINGS, interval_us, - 0, 0, 0, 0, 0 + 0, 0, 0, 0, 0, + false // Don't wait for response ).ConfigureAwait(false); }); } @@ -251,7 +252,8 @@ await parent.parent.doCommandAsync( MAVLink.MAV_CMD.SET_MESSAGE_INTERVAL, (float)MAVLink.MAVLINK_MSG_ID.CAMERA_CAPTURE_STATUS, interval_us, - 0, 0, 0, 0, 0 + 0, 0, 0, 0, 0, + false // Don't wait for response ).ConfigureAwait(false); }); }