From b02c0dd176980b360dc0d932d19d30824e3f6e0b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 30 May 2024 14:17:07 +1200 Subject: [PATCH] Camera: switch to new REQUEST_MESSAGE commands The used commands like REQUEST_CAMERA_SETTINGS and REQUEST_CAMERA_INFORMATION are deprecated. Therefore, we should gradually try to move to the new REQUEST_MESSAGE commands. This commit does so by sending REQUEST_MESSAGE by default but falling back to the previous commands on the second try and every other retry after that. --- src/Camera/QGCCameraControl.cc | 98 +++++++++++++++++++++++++--------- src/Camera/QGCCameraControl.h | 6 ++- src/Camera/QGCCameraManager.cc | 26 ++++++--- src/Camera/QGCCameraManager.h | 2 +- 4 files changed, 96 insertions(+), 36 deletions(-) diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index a7b2757ea02..aa308d0c814 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -744,7 +744,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i break; case MAV_CMD_IMAGE_START_CAPTURE: case MAV_CMD_IMAGE_STOP_CAPTURE: - if(++_captureInfoRetries < 3) { + if(++_captureInfoRetries < 5) { _captureStatusTimer.start(1000); } else { qCDebug(CameraControlLog) << "Giving up start/stop image capture"; @@ -752,14 +752,14 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i } break; case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS: - if(++_captureInfoRetries < 3) { + if(++_captureInfoRetries < 5) { _captureStatusTimer.start(500); } else { qCDebug(CameraControlLog) << "Giving up requesting capture status"; } break; case MAV_CMD_REQUEST_STORAGE_INFORMATION: - if(++_storageInfoRetries < 3) { + if(++_storageInfoRetries < 5) { QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo); } else { qCDebug(CameraControlLog) << "Giving up requesting storage status"; @@ -1459,12 +1459,24 @@ QGCCameraControl::_requestCameraSettings() { qCDebug(CameraControlLog) << "_requestCameraSettings()"; if(_vehicle) { - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_REQUEST_CAMERA_SETTINGS, // command id - false, // showError - 1); // Do Request + // Use REQUEST_MESSAGE instead of deprecated REQUEST_CAMERA_SETTINGS + // first time and every other time after that. + + if(_cameraSettingsRetries++ % 2 == 0) { + _vehicle->sendMavCommand( + _compID, // target component + MAV_CMD_REQUEST_MESSAGE, // command id + false, // showError + MAVLINK_MSG_ID_CAMERA_SETTINGS); // msgid + } else { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_REQUEST_CAMERA_SETTINGS, // command id + false, // showError + 1); // Do Request + } } + } //----------------------------------------------------------------------------- @@ -1473,12 +1485,23 @@ QGCCameraControl::_requestStorageInfo() { qCDebug(CameraControlLog) << "_requestStorageInfo()"; if(_vehicle) { - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_REQUEST_STORAGE_INFORMATION, // command id - false, // showError - 0, // Storage ID (0 for all, 1 for first, 2 for second, etc.) - 1); // Do Request + // Use REQUEST_MESSAGE instead of deprecated REQUEST_CAMERA_SETTINGS + // first time and every other time after that. + if(_storageInfoRetries++ % 2 == 0) { + _vehicle->sendMavCommand( + _compID, // target component + MAV_CMD_REQUEST_MESSAGE, // command id + false, // showError + MAVLINK_MSG_ID_STORAGE_INFORMATION, // msgid + 0); // storage ID + } else { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_REQUEST_STORAGE_INFORMATION, // command id + false, // showError + 0, // Storage ID (0 for all, 1 for first, 2 for second, etc.) + 1); // Do Request + } } } @@ -1604,6 +1627,7 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi) //-- Done qCDebug(CameraControlLog) << "All stream handlers done"; _streamInfoTimer.stop(); + _videoStreamInfoRetries = 0; emit autoStreamChanged(); emit _vehicle->cameraManager()->streamChanged(); } @@ -1619,6 +1643,7 @@ QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs) if(pInfo) { pInfo->update(vs); } + _videoStreamStatusRetries = 0; } //----------------------------------------------------------------------------- @@ -1769,11 +1794,22 @@ void QGCCameraControl::_requestStreamInfo(uint8_t streamID) { qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID; - _vehicle->sendMavCommand( - _compID, // Target component - MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id - false, // ShowError - streamID); // Stream ID + // By default, try to use new REQUEST_MESSAGE command instead of + // deprecated MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION. + if (_videoStreamStatusRetries % 2 == 0) { + _vehicle->sendMavCommand( + _compID, // target component + MAV_CMD_REQUEST_MESSAGE, // command id + false, // showError + MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, // msgid + streamID); // stream ID + } else { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id + false, // ShowError + streamID); // Stream ID + } } //----------------------------------------------------------------------------- @@ -1781,11 +1817,22 @@ void QGCCameraControl::_requestStreamStatus(uint8_t streamID) { qCDebug(CameraControlLog) << "Requesting video stream status for:" << streamID; + // By default, try to use new REQUEST_MESSAGE command instead of + // deprecated MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION. + if (_videoStreamInfoRetries % 2 == 0) { + _vehicle->sendMavCommand( + _compID, // target component + MAV_CMD_REQUEST_MESSAGE, // command id + false, // showError + MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, // msgid + streamID); // stream id + } else { _vehicle->sendMavCommand( _compID, // Target component MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, // Command id false, // ShowError streamID); // Stream ID + } _streamStatusTimer.start(1000); // Wait up to a second for it } @@ -1830,11 +1877,11 @@ QGCCameraControl::_findStream(const QString name) //----------------------------------------------------------------------------- void -QGCCameraControl::_streamTimeout() +QGCCameraControl::_streamInfoTimeout() { - _requestCount++; - int count = _expectedCount * 3; - if(_requestCount > count) { + _videoStreamInfoRetries++; + int count = _expectedCount * 5; + if(_videoStreamInfoRetries > count) { qCWarning(CameraControlLog) << "Giving up requesting video stream info"; _streamInfoTimer.stop(); //-- If we have at least one stream, work with what we have. @@ -1857,6 +1904,7 @@ QGCCameraControl::_streamTimeout() void QGCCameraControl::_streamStatusTimeout() { + _videoStreamStatusRetries++; QGCVideoStreamInfo* pStream = currentStreamInstance(); if(pStream) { _requestStreamStatus(static_cast(pStream->streamID())); @@ -2181,7 +2229,7 @@ QGCCameraControl::_checkForVideoStreams() if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) { //-- Skip it if using Taisync as it has its own video settings if(!qgcApp()->toolbox()->videoManager()->isTaisync()) { - connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout); + connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamInfoTimeout); _streamInfoTimer.setSingleShot(false); connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout); _streamStatusTimer.setSingleShot(true); @@ -2412,4 +2460,4 @@ QGCCameraControl::_requestTrackingStatus() true, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, 500000); // Interval (us) -} \ No newline at end of file +} diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index 1b389bcd38c..eaaafa65c95 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -382,7 +382,7 @@ protected slots: virtual void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); virtual void _dataReady (QByteArray data); virtual void _paramDone (); - virtual void _streamTimeout (); + virtual void _streamInfoTimeout (); virtual void _streamStatusTimeout (); virtual void _recTimerHandler (); virtual void _checkForVideoStreams (); @@ -439,6 +439,7 @@ protected slots: QMap _originalOptNames; QMap _originalOptValues; QMap _paramIO; + int _cameraSettingsRetries = 0; int _storageInfoRetries = 0; int _captureInfoRetries = 0; bool _resetting = false; @@ -449,7 +450,8 @@ protected slots: QMap _requestUpdates; QStringList _updatesToRequest; //-- Video Streams - int _requestCount = 0; + int _videoStreamInfoRetries = 0; + int _videoStreamStatusRetries = 0; int _currentStream = 0; int _expectedCount = 1; QTimer _streamInfoTimer; diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index 5c9ee5b4b6a..b2b7bef6289 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -120,7 +120,7 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) pInfo->lastHeartbeat.start(); _cameraInfoRequest[sCompID] = pInfo; //-- Request camera info - _requestCameraInfo(message.compid); + _requestCameraInfo(message.compid, pInfo->tryCount); } else { if(_cameraInfoRequest[sCompID]) { CameraStruct* pInfo = _cameraInfoRequest[sCompID]; @@ -139,7 +139,7 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) } else { pInfo->tryCount++; //-- Request camera info again. - _requestCameraInfo(message.compid); + _requestCameraInfo(message.compid, pInfo->tryCount); } } } @@ -387,15 +387,25 @@ QGCCameraManager::_handleTrackingImageStatus(const mavlink_message_t& message) //----------------------------------------------------------------------------- void -QGCCameraManager::_requestCameraInfo(int compID) +QGCCameraManager::_requestCameraInfo(int compID, int tryCount) { qCDebug(CameraManagerLog) << "_requestCameraInfo(" << compID << ")"; if(_vehicle) { - _vehicle->sendMavCommand( - compID, // target component - MAV_CMD_REQUEST_CAMERA_INFORMATION, // command id - false, // showError - 1); // Do Request + // The MAV_CMD_REQUEST_CAMERA_INFORMATION command is deprecated, so we + // only fall back to it on the second and every other try. + if (tryCount % 2 == 0) { + _vehicle->sendMavCommand( + compID, // target component + MAV_CMD_REQUEST_MESSAGE, // command id + false, // showError + MAVLINK_MSG_ID_CAMERA_INFORMATION); // msgid + } else { + _vehicle->sendMavCommand( + compID, // target component + MAV_CMD_REQUEST_CAMERA_INFORMATION, // command id + false, // showError + 1); // Do Request + } } } diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h index 91c726b1fd4..08054e0bed8 100644 --- a/src/Camera/QGCCameraManager.h +++ b/src/Camera/QGCCameraManager.h @@ -74,7 +74,7 @@ protected slots: protected: virtual QGCCameraControl* _findCamera (int id); - virtual void _requestCameraInfo (int compID); + virtual void _requestCameraInfo (int compID, int tryCount); virtual void _handleHeartbeat (const mavlink_message_t& message); virtual void _handleCameraInfo (const mavlink_message_t& message); virtual void _handleStorageInfo (const mavlink_message_t& message);