From 2f17ab70d7f4441ddda24eb574aeefd41c2bc61f Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Mon, 28 Aug 2017 04:41:52 -0400 Subject: [PATCH] Handle capture status retries when capturing images. Allow plugin to validate parameter setting. --- src/Camera/QGCCameraControl.cc | 22 ++++++++++++++++++++-- src/Camera/QGCCameraControl.h | 2 ++ src/Camera/QGCCameraIO.cc | 4 +++- 3 files changed, 25 insertions(+), 3 deletions(-) diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index 32f646f04..cc485650d 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -272,6 +272,7 @@ QGCCameraControl::takePhoto() 0, // Duration between two consecutive pictures (in seconds--ignored if single image) 1); // Number of images to capture total - 0 for unlimited capture _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); + _captureInfoRetries = 0; //-- Capture local image as well QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); QDir().mkpath(photoPath); @@ -384,6 +385,7 @@ QGCCameraControl::formatCard(int id) void QGCCameraControl::_requestCaptureStatus() { + qCDebug(CameraControlLog) << "_requestCaptureStatus()"; _vehicle->sendMavCommand( _compID, // target component MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, // command id @@ -445,16 +447,23 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i qCDebug(CameraControlLog) << "Command failed for" << command; } switch(command) { + case MAV_CMD_IMAGE_START_CAPTURE: + if(++_captureInfoRetries < 5) { + _captureStatusTimer.start(1000); + } else { + qCDebug(CameraControlLog) << "Giving up requesting capture status"; + } + break; case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS: if(++_captureInfoRetries < 3) { - _requestCaptureStatus(); + _captureStatusTimer.start(500); } else { qCDebug(CameraControlLog) << "Giving up requesting capture status"; } break; case MAV_CMD_REQUEST_STORAGE_INFORMATION: if(++_storageInfoRetries < 3) { - _requestStorageInfo(); + QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo); } else { qCDebug(CameraControlLog) << "Giving up requesting storage status"; } @@ -1349,3 +1358,12 @@ QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue) Q_UNUSED(newValue); return true; } + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::validateParameter(Fact* pFact, QVariant& newValue) +{ + Q_UNUSED(pFact); + Q_UNUSED(newValue); + return true; +} diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index a145b8dbb..5b4cda367 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -161,6 +161,8 @@ public: virtual void factChanged (Fact* pFact); //-- Allow controller to modify or invalidate incoming parameter virtual bool incomingParameter (Fact* pFact, QVariant& newValue); + //-- Allow controller to modify or invalidate parameter change + virtual bool validateParameter (Fact* pFact, QVariant& newValue); signals: void infoChanged (); diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc index db6e66b95..7337d394f 100644 --- a/src/Camera/QGCCameraIO.cc +++ b/src/Camera/QGCCameraIO.cc @@ -204,7 +204,9 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack) //-- If UI changed and value was not set, restore UI QVariant val = _valueFromMessage(ack.param_value, ack.param_type); if(_fact->rawValue() != val) { - _fact->_containerSetRawValue(val); + if(_control->validateParameter(_fact, val)) { + _fact->_containerSetRawValue(val); + } } } } -- 2.22.0