Commit 8311619d authored by Gus Grubba's avatar Gus Grubba Committed by Gus Grubba

Avoid sending camera commands while a reset is pending.

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