Unverified Commit 5e63260b authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7085 from mavlink/waitOnReset

Avoid sending camera commands while a reset is pending.
parents f39452b3 8311619d
...@@ -157,6 +157,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -157,6 +157,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED) , _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
, _storageInfoRetries(0) , _storageInfoRetries(0)
, _captureInfoRetries(0) , _captureInfoRetries(0)
, _resetting(false)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
memcpy(&_info, info, sizeof(mavlink_camera_information_t)); memcpy(&_info, info, sizeof(mavlink_camera_information_t));
...@@ -251,6 +252,7 @@ QGCCameraControl::storageFreeStr() ...@@ -251,6 +252,7 @@ QGCCameraControl::storageFreeStr()
void void
QGCCameraControl::setCameraMode(CameraMode mode) QGCCameraControl::setCameraMode(CameraMode mode)
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")"; qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")";
if(mode == CAM_MODE_VIDEO) { if(mode == CAM_MODE_VIDEO) {
setVideoMode(); setVideoMode();
...@@ -260,16 +262,19 @@ QGCCameraControl::setCameraMode(CameraMode mode) ...@@ -260,16 +262,19 @@ QGCCameraControl::setCameraMode(CameraMode mode)
qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
return; return;
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::setPhotoMode(PhotoMode mode) QGCCameraControl::setPhotoMode(PhotoMode mode)
{ {
if(!_resetting) {
_photoMode = mode; _photoMode = mode;
QSettings settings; QSettings settings;
settings.setValue(kPhotoMode, static_cast<int>(mode)); settings.setValue(kPhotoMode, static_cast<int>(mode));
emit photoModeChanged(); emit photoModeChanged();
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -304,22 +309,27 @@ QGCCameraControl::_setCameraMode(CameraMode mode) ...@@ -304,22 +309,27 @@ QGCCameraControl::_setCameraMode(CameraMode mode)
void void
QGCCameraControl::toggleMode() QGCCameraControl::toggleMode()
{ {
if(!_resetting) {
if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) { if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) {
setVideoMode(); setVideoMode();
} else if(cameraMode() == CAM_MODE_VIDEO) { } else if(cameraMode() == CAM_MODE_VIDEO) {
setPhotoMode(); setPhotoMode();
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
QGCCameraControl::toggleVideo() QGCCameraControl::toggleVideo()
{ {
if(!_resetting) {
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
return stopVideo(); return stopVideo();
} else { } else {
return startVideo(); return startVideo();
} }
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -331,6 +341,7 @@ QGCCameraControl::takePhoto() ...@@ -331,6 +341,7 @@ QGCCameraControl::takePhoto()
if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) { if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) {
return false; return false;
} }
if(!_resetting) {
if(capturesPhotos()) { if(capturesPhotos()) {
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
_compID, // Target component _compID, // Target component
...@@ -348,6 +359,7 @@ QGCCameraControl::takePhoto() ...@@ -348,6 +359,7 @@ QGCCameraControl::takePhoto()
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath);
return true; return true;
} }
}
return false; return false;
} }
...@@ -355,6 +367,7 @@ QGCCameraControl::takePhoto() ...@@ -355,6 +367,7 @@ QGCCameraControl::takePhoto()
bool bool
QGCCameraControl::stopTakePhoto() QGCCameraControl::stopTakePhoto()
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "stopTakePhoto()"; qCDebug(CameraControlLog) << "stopTakePhoto()";
if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) { if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) {
return false; return false;
...@@ -369,6 +382,7 @@ QGCCameraControl::stopTakePhoto() ...@@ -369,6 +382,7 @@ QGCCameraControl::stopTakePhoto()
_captureInfoRetries = 0; _captureInfoRetries = 0;
return true; return true;
} }
}
return false; return false;
} }
...@@ -376,6 +390,7 @@ QGCCameraControl::stopTakePhoto() ...@@ -376,6 +390,7 @@ QGCCameraControl::stopTakePhoto()
bool bool
QGCCameraControl::startVideo() QGCCameraControl::startVideo()
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "startVideo()"; qCDebug(CameraControlLog) << "startVideo()";
//-- Check if camera can capture videos or if it can capture it while in Photo Mode //-- Check if camera can capture videos or if it can capture it while in Photo Mode
if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) { if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) {
...@@ -390,6 +405,7 @@ QGCCameraControl::startVideo() ...@@ -390,6 +405,7 @@ QGCCameraControl::startVideo()
0); // CAMERA_CAPTURE_STATUS Frequency 0); // CAMERA_CAPTURE_STATUS Frequency
return true; return true;
} }
}
return false; return false;
} }
...@@ -397,6 +413,7 @@ QGCCameraControl::startVideo() ...@@ -397,6 +413,7 @@ QGCCameraControl::startVideo()
bool bool
QGCCameraControl::stopVideo() QGCCameraControl::stopVideo()
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "stopVideo()"; qCDebug(CameraControlLog) << "stopVideo()";
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
...@@ -406,6 +423,7 @@ QGCCameraControl::stopVideo() ...@@ -406,6 +423,7 @@ QGCCameraControl::stopVideo()
0); // Reserved (Set to 0) 0); // Reserved (Set to 0)
return true; return true;
} }
}
return false; return false;
} }
...@@ -413,6 +431,7 @@ QGCCameraControl::stopVideo() ...@@ -413,6 +431,7 @@ QGCCameraControl::stopVideo()
void void
QGCCameraControl::setVideoMode() QGCCameraControl::setVideoMode()
{ {
if(!_resetting) {
if(hasModes() && _cameraMode != CAM_MODE_VIDEO) { if(hasModes() && _cameraMode != CAM_MODE_VIDEO) {
qCDebug(CameraControlLog) << "setVideoMode()"; qCDebug(CameraControlLog) << "setVideoMode()";
//-- Use basic MAVLink message //-- Use basic MAVLink message
...@@ -424,12 +443,14 @@ QGCCameraControl::setVideoMode() ...@@ -424,12 +443,14 @@ QGCCameraControl::setVideoMode()
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video) CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_VIDEO); _setCameraMode(CAM_MODE_VIDEO);
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::setPhotoMode() QGCCameraControl::setPhotoMode()
{ {
if(!_resetting) {
if(hasModes() && _cameraMode != CAM_MODE_PHOTO) { if(hasModes() && _cameraMode != CAM_MODE_PHOTO) {
qCDebug(CameraControlLog) << "setPhotoMode()"; qCDebug(CameraControlLog) << "setPhotoMode()";
//-- Use basic MAVLink message //-- Use basic MAVLink message
...@@ -441,24 +462,29 @@ QGCCameraControl::setPhotoMode() ...@@ -441,24 +462,29 @@ QGCCameraControl::setPhotoMode()
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video) CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_PHOTO); _setCameraMode(CAM_MODE_PHOTO);
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::resetSettings() QGCCameraControl::resetSettings()
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "resetSettings()"; qCDebug(CameraControlLog) << "resetSettings()";
_resetting = true;
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
_compID, // Target component _compID, // Target component
MAV_CMD_RESET_CAMERA_SETTINGS, // Command id MAV_CMD_RESET_CAMERA_SETTINGS, // Command id
true, // ShowError true, // ShowError
1); // Do Reset 1); // Do Reset
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::formatCard(int id) QGCCameraControl::formatCard(int id)
{ {
if(!_resetting) {
qCDebug(CameraControlLog) << "formatCard()"; qCDebug(CameraControlLog) << "formatCard()";
if(_vehicle) { if(_vehicle) {
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
...@@ -468,6 +494,7 @@ QGCCameraControl::formatCard(int id) ...@@ -468,6 +494,7 @@ QGCCameraControl::formatCard(int id)
id, // Storage ID (1 for first, 2 for second, etc.) id, // Storage ID (1 for first, 2 for second, etc.)
1); // Do Format 1); // Do Format
} }
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -504,6 +531,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i ...@@ -504,6 +531,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
}else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) { }else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) {
switch(command) { switch(command) {
case MAV_CMD_RESET_CAMERA_SETTINGS: case MAV_CMD_RESET_CAMERA_SETTINGS:
_resetting = false;
if(isBasic()) { if(isBasic()) {
_requestCameraSettings(); _requestCameraSettings();
} else { } else {
......
...@@ -246,6 +246,7 @@ protected: ...@@ -246,6 +246,7 @@ protected:
QMap<QString, QGCCameraParamIO*> _paramIO; QMap<QString, QGCCameraParamIO*> _paramIO;
int _storageInfoRetries; int _storageInfoRetries;
int _captureInfoRetries; int _captureInfoRetries;
bool _resetting;
//-- Parameters that require a full update //-- Parameters that require a full update
QMap<QString, QStringList> _requestUpdates; QMap<QString, QStringList> _requestUpdates;
QStringList _updatesToRequest; QStringList _updatesToRequest;
......
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