Commit 2f17ab70 authored by Gus Grubba's avatar Gus Grubba

Handle capture status retries when capturing images.

Allow plugin to validate parameter setting.
parent 4bf28634
...@@ -272,6 +272,7 @@ QGCCameraControl::takePhoto() ...@@ -272,6 +272,7 @@ QGCCameraControl::takePhoto()
0, // Duration between two consecutive pictures (in seconds--ignored if single image) 0, // Duration between two consecutive pictures (in seconds--ignored if single image)
1); // Number of images to capture total - 0 for unlimited capture 1); // Number of images to capture total - 0 for unlimited capture
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
_captureInfoRetries = 0;
//-- Capture local image as well //-- Capture local image as well
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QDir().mkpath(photoPath); QDir().mkpath(photoPath);
...@@ -384,6 +385,7 @@ QGCCameraControl::formatCard(int id) ...@@ -384,6 +385,7 @@ QGCCameraControl::formatCard(int id)
void void
QGCCameraControl::_requestCaptureStatus() QGCCameraControl::_requestCaptureStatus()
{ {
qCDebug(CameraControlLog) << "_requestCaptureStatus()";
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
_compID, // target component _compID, // target component
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, // command id MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, // command id
...@@ -445,16 +447,23 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i ...@@ -445,16 +447,23 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
qCDebug(CameraControlLog) << "Command failed for" << command; qCDebug(CameraControlLog) << "Command failed for" << command;
} }
switch(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: case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
if(++_captureInfoRetries < 3) { if(++_captureInfoRetries < 3) {
_requestCaptureStatus(); _captureStatusTimer.start(500);
} else { } else {
qCDebug(CameraControlLog) << "Giving up requesting capture status"; qCDebug(CameraControlLog) << "Giving up requesting capture status";
} }
break; break;
case MAV_CMD_REQUEST_STORAGE_INFORMATION: case MAV_CMD_REQUEST_STORAGE_INFORMATION:
if(++_storageInfoRetries < 3) { if(++_storageInfoRetries < 3) {
_requestStorageInfo(); QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo);
} else { } else {
qCDebug(CameraControlLog) << "Giving up requesting storage status"; qCDebug(CameraControlLog) << "Giving up requesting storage status";
} }
...@@ -1349,3 +1358,12 @@ QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue) ...@@ -1349,3 +1358,12 @@ QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
Q_UNUSED(newValue); Q_UNUSED(newValue);
return true; return true;
} }
//-----------------------------------------------------------------------------
bool
QGCCameraControl::validateParameter(Fact* pFact, QVariant& newValue)
{
Q_UNUSED(pFact);
Q_UNUSED(newValue);
return true;
}
...@@ -161,6 +161,8 @@ public: ...@@ -161,6 +161,8 @@ public:
virtual void factChanged (Fact* pFact); virtual void factChanged (Fact* pFact);
//-- Allow controller to modify or invalidate incoming parameter //-- Allow controller to modify or invalidate incoming parameter
virtual bool incomingParameter (Fact* pFact, QVariant& newValue); virtual bool incomingParameter (Fact* pFact, QVariant& newValue);
//-- Allow controller to modify or invalidate parameter change
virtual bool validateParameter (Fact* pFact, QVariant& newValue);
signals: signals:
void infoChanged (); void infoChanged ();
......
...@@ -204,9 +204,11 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack) ...@@ -204,9 +204,11 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
//-- If UI changed and value was not set, restore UI //-- If UI changed and value was not set, restore UI
QVariant val = _valueFromMessage(ack.param_value, ack.param_type); QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
if(_fact->rawValue() != val) { if(_fact->rawValue() != val) {
if(_control->validateParameter(_fact, val)) {
_fact->_containerSetRawValue(val); _fact->_containerSetRawValue(val);
} }
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment