Commit 4bf28634 authored by Gus Grubba's avatar Gus Grubba

Keep track of photo status (image capture)

Don't allow "Take Photo" is status is not idle.
Handle In Progress response (basically, do nothing)
Request capture status when stopping video recording.
parent cc54a4e0
...@@ -120,6 +120,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -120,6 +120,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _netManager(NULL) , _netManager(NULL)
, _cameraMode(CAM_MODE_UNDEFINED) , _cameraMode(CAM_MODE_UNDEFINED)
, _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED) , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
, _storageInfoRetries(0) , _storageInfoRetries(0)
, _captureInfoRetries(0) , _captureInfoRetries(0)
{ {
...@@ -194,6 +195,13 @@ QGCCameraControl::videoStatus() ...@@ -194,6 +195,13 @@ QGCCameraControl::videoStatus()
return _video_status; return _video_status;
} }
//-----------------------------------------------------------------------------
QGCCameraControl::PhotoStatus
QGCCameraControl::photoStatus()
{
return _photo_status;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QString QString
QGCCameraControl::storageFreeStr() QGCCameraControl::storageFreeStr()
...@@ -252,7 +260,7 @@ QGCCameraControl::takePhoto() ...@@ -252,7 +260,7 @@ QGCCameraControl::takePhoto()
{ {
qCDebug(CameraControlLog) << "takePhoto()"; qCDebug(CameraControlLog) << "takePhoto()";
//-- Check if camera can capture photos or if it can capture it while in Video Mode //-- Check if camera can capture photos or if it can capture it while in Video Mode
if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode())) { if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) {
return false; return false;
} }
if(capturesPhotos()) { if(capturesPhotos()) {
...@@ -263,6 +271,7 @@ QGCCameraControl::takePhoto() ...@@ -263,6 +271,7 @@ QGCCameraControl::takePhoto()
0, // Reserved (Set to 0) 0, // Reserved (Set to 0)
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);
//-- 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);
...@@ -398,7 +407,10 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i ...@@ -398,7 +407,10 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
if(_vehicle->id() != vehicleId || compID() != component) { if(_vehicle->id() != vehicleId || compID() != component) {
return; return;
} }
if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) { if(!noReponseFromVehicle && result == MAV_RESULT_IN_PROGRESS) {
//-- Do Nothing
qCDebug(CameraControlLog) << "In progress response for" << command;
}else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) {
switch(command) { switch(command) {
case MAV_CMD_RESET_CAMERA_SETTINGS: case MAV_CMD_RESET_CAMERA_SETTINGS:
if(isBasic()) { if(isBasic()) {
...@@ -414,6 +426,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i ...@@ -414,6 +426,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
break; break;
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE:
_setVideoStatus(VIDEO_CAPTURE_STATUS_STOPPED); _setVideoStatus(VIDEO_CAPTURE_STATUS_STOPPED);
_captureStatusTimer.start(1000);
break; break;
case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS: case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
_captureInfoRetries = 0; _captureInfoRetries = 0;
...@@ -463,6 +476,16 @@ QGCCameraControl::_setVideoStatus(VideoStatus status) ...@@ -463,6 +476,16 @@ QGCCameraControl::_setVideoStatus(VideoStatus status)
} }
} }
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setPhotoStatus(PhotoStatus status)
{
if(_photo_status != status) {
_photo_status = status;
emit photoStatusChanged();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes) QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
...@@ -1069,7 +1092,10 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap ...@@ -1069,7 +1092,10 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
emit storageFreeChanged(); emit storageFreeChanged();
} }
//-- Video Capture Status //-- Video Capture Status
_setVideoStatus((VideoStatus)cap.video_status); uint8_t vs = cap.video_status < (uint8_t)VIDEO_CAPTURE_STATUS_LAST ? cap.video_status : (uint8_t)VIDEO_CAPTURE_STATUS_UNDEFINED;
uint8_t ps = cap.image_status < (uint8_t)PHOTO_CAPTURE_LAST ? cap.image_status : (uint8_t)PHOTO_CAPTURE_STATUS_UNDEFINED;
_setVideoStatus((VideoStatus)vs);
_setPhotoStatus((PhotoStatus)ps);
//-- Keep asking for it once in a while when recording //-- Keep asking for it once in a while when recording
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_captureStatusTimer.start(5000); _captureStatusTimer.start(5000);
......
...@@ -76,11 +76,23 @@ public: ...@@ -76,11 +76,23 @@ public:
enum VideoStatus { enum VideoStatus {
VIDEO_CAPTURE_STATUS_STOPPED = 0, VIDEO_CAPTURE_STATUS_STOPPED = 0,
VIDEO_CAPTURE_STATUS_RUNNING, VIDEO_CAPTURE_STATUS_RUNNING,
VIDEO_CAPTURE_STATUS_UNDEFINED VIDEO_CAPTURE_STATUS_LAST,
VIDEO_CAPTURE_STATUS_UNDEFINED = 255
};
//-- Photo Capture Status
enum PhotoStatus {
PHOTO_CAPTURE_IDLE = 0,
PHOTO_CAPTURE_IN_PROGRESS,
PHOTO_CAPTURE_INTERVAL_IDLE,
PHOTO_CAPTURE_INTERVAL_IN_PROGRESS,
PHOTO_CAPTURE_LAST,
PHOTO_CAPTURE_STATUS_UNDEFINED = 255
}; };
Q_ENUMS(CameraMode) Q_ENUMS(CameraMode)
Q_ENUMS(VideoStatus) Q_ENUMS(VideoStatus)
Q_ENUMS(PhotoStatus)
Q_PROPERTY(int version READ version NOTIFY infoChanged) Q_PROPERTY(int version READ version NOTIFY infoChanged)
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
...@@ -101,6 +113,7 @@ public: ...@@ -101,6 +113,7 @@ public:
Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged) Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged) Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
Q_PROPERTY(PhotoStatus photoStatus READ photoStatus NOTIFY photoStatusChanged)
Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged) Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged)
Q_INVOKABLE virtual void setVideoMode (); Q_INVOKABLE virtual void setVideoMode ();
...@@ -129,6 +142,7 @@ public: ...@@ -129,6 +142,7 @@ public:
virtual int compID () { return _compID; } virtual int compID () { return _compID; }
virtual bool isBasic () { return _settings.size() == 0; } virtual bool isBasic () { return _settings.size() == 0; }
virtual VideoStatus videoStatus (); virtual VideoStatus videoStatus ();
virtual PhotoStatus photoStatus ();
virtual CameraMode cameraMode () { return _cameraMode; } virtual CameraMode cameraMode () { return _cameraMode; }
virtual QStringList activeSettings () { return _activeSettings; } virtual QStringList activeSettings () { return _activeSettings; }
virtual quint32 storageFree () { return _storageFree; } virtual quint32 storageFree () { return _storageFree; }
...@@ -151,6 +165,7 @@ public: ...@@ -151,6 +165,7 @@ public:
signals: signals:
void infoChanged (); void infoChanged ();
void videoStatusChanged (); void videoStatusChanged ();
void photoStatusChanged ();
void cameraModeChanged (); void cameraModeChanged ();
void activeSettingsChanged (); void activeSettingsChanged ();
void storageFreeChanged (); void storageFreeChanged ();
...@@ -160,6 +175,7 @@ signals: ...@@ -160,6 +175,7 @@ signals:
protected: protected:
virtual void _setVideoStatus (VideoStatus status); virtual void _setVideoStatus (VideoStatus status);
virtual void _setPhotoStatus (PhotoStatus status);
virtual void _setCameraMode (CameraMode mode); virtual void _setCameraMode (CameraMode mode);
protected slots: protected slots:
...@@ -208,6 +224,7 @@ protected: ...@@ -208,6 +224,7 @@ protected:
QString _cacheFile; QString _cacheFile;
CameraMode _cameraMode; CameraMode _cameraMode;
VideoStatus _video_status; VideoStatus _video_status;
PhotoStatus _photo_status;
QStringList _activeSettings; QStringList _activeSettings;
QStringList _settings; QStringList _settings;
QTimer _captureStatusTimer; QTimer _captureStatusTimer;
......
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