diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index 8a80d2a7d8ddd9b7350e2f3aa3877dfbb96baafb..b4db590ec80b2c6e83eead7fa93884458f96a6d9 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -115,7 +115,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh , _storageFree(0) , _storageTotal(0) , _netManager(NULL) - , _cameraMode(CAMERA_MODE_UNDEFINED) + , _cameraMode(CAM_MODE_UNDEFINED) , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED) { memcpy(&_info, info, sizeof(mavlink_camera_information_t)); @@ -200,9 +200,9 @@ void QGCCameraControl::setCameraMode(CameraMode mode) { qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")"; - if(mode == CAMERA_MODE_VIDEO) { + if(mode == CAM_MODE_VIDEO) { setVideoMode(); - } else if(mode == CAMERA_MODE_PHOTO) { + } else if(mode == CAM_MODE_PHOTO) { setPhotoMode(); } else { qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; @@ -222,9 +222,9 @@ QGCCameraControl::_setCameraMode(CameraMode mode) void QGCCameraControl::toggleMode() { - if(cameraMode() == CAMERA_MODE_PHOTO) { + if(cameraMode() == CAM_MODE_PHOTO) { setVideoMode(); - } else if(cameraMode() == CAMERA_MODE_VIDEO) { + } else if(cameraMode() == CAM_MODE_VIDEO) { setPhotoMode(); } } @@ -246,7 +246,7 @@ QGCCameraControl::takePhoto() { qCDebug(CameraControlLog) << "takePhoto()"; //-- Check if camera can capture photos or if it can capture it while in Video Mode - if(!capturesPhotos() || (cameraMode() == CAMERA_MODE_VIDEO && !photosInVideoMode())) { + if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode())) { return false; } if(capturesPhotos()) { @@ -273,7 +273,7 @@ QGCCameraControl::startVideo() { qCDebug(CameraControlLog) << "startVideo()"; //-- Check if camera can capture videos or if it can capture it while in Photo Mode - if(!capturesVideo() || (cameraMode() == CAMERA_MODE_PHOTO && !videoInPhotoMode())) { + if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) { return false; } if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) { @@ -308,7 +308,7 @@ QGCCameraControl::stopVideo() void QGCCameraControl::setVideoMode() { - if(hasModes() && _cameraMode != CAMERA_MODE_VIDEO) { + if(hasModes() && _cameraMode != CAM_MODE_VIDEO) { qCDebug(CameraControlLog) << "setVideoMode()"; //-- Use basic MAVLink message _vehicle->sendMavCommand( @@ -316,8 +316,8 @@ QGCCameraControl::setVideoMode() MAV_CMD_SET_CAMERA_MODE, // Command id true, // ShowError 0, // Reserved (Set to 0) - CAMERA_MODE_VIDEO); // Camera mode (0: photo, 1: video) - _setCameraMode(CAMERA_MODE_VIDEO); + CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_VIDEO); } } @@ -325,7 +325,7 @@ QGCCameraControl::setVideoMode() void QGCCameraControl::setPhotoMode() { - if(hasModes() && _cameraMode != CAMERA_MODE_PHOTO) { + if(hasModes() && _cameraMode != CAM_MODE_PHOTO) { qCDebug(CameraControlLog) << "setPhotoMode()"; //-- Use basic MAVLink message _vehicle->sendMavCommand( @@ -333,8 +333,8 @@ QGCCameraControl::setPhotoMode() MAV_CMD_SET_CAMERA_MODE, // Command id true, // ShowError 0, // Reserved (Set to 0) - CAMERA_MODE_PHOTO); // Camera mode (0: photo, 1: video) - _setCameraMode(CAMERA_MODE_PHOTO); + CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_PHOTO); } } @@ -594,6 +594,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle); _paramIO[factName] = pIO; _addFact(pFact, factName); + pFact->setSendValueChangedSignals(false); } } if(_nameToFactMetaDataMap.size() > 0) { @@ -759,14 +760,17 @@ QGCCameraControl::_updateActiveList() } } } - qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList; - _activeSettings.clear(); + QStringList active; foreach(QString key, _settings) { if(!exclusionList.contains(key)) { - _activeSettings.append(key); + active.append(key); } } - emit activeSettingsChanged(); + if(active != _activeSettings) { + qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList; + _activeSettings = active; + emit activeSettingsChanged(); + } } //----------------------------------------------------------------------------- @@ -865,18 +869,20 @@ QGCCameraControl::_updateRanges(Fact* pFact) //-- If this value (and condition) triggers a change in the target range if(pRange->value == option && _processCondition(pRange->condition)) { //-- Set limited range set - pTFact->setEnumInfo(pRange->optNames, pRange->optVariants); - emit pTFact->enumStringsChanged(); - emit pTFact->enumValuesChanged(); - qCDebug(CameraControlLogVerbose) << "Limited:" << pRange->targetParam << pRange->optNames; + if(pTFact->enumStrings() != pRange->optNames) { + pTFact->setEnumInfo(pRange->optNames, pRange->optVariants); + emit pTFact->enumsChanged(); + qCDebug(CameraControlLogVerbose) << "Limited:" << pRange->targetParam << pRange->optNames; + } changedList << pRange->targetParam; } else { if(!resetList.contains(pRange->targetParam)) { - //-- Restore full option set - pTFact->setEnumInfo(_originalOptNames[pRange->targetParam], _originalOptValues[pRange->targetParam]); - emit pTFact->enumStringsChanged(); - emit pTFact->enumValuesChanged(); - qCDebug(CameraControlLogVerbose) << "Full:" << pRange->targetParam << _originalOptNames[pRange->targetParam]; + if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) { + //-- Restore full option set + pTFact->setEnumInfo(_originalOptNames[pRange->targetParam], _originalOptValues[pRange->targetParam]); + emit pTFact->enumsChanged(); + qCDebug(CameraControlLogVerbose) << "Full:" << pRange->targetParam << _originalOptNames[pRange->targetParam]; + } resetList << pRange->targetParam; } } diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index 5d70330f2526a1b99a5ea1e97a498e790e006b7d..1af2fbc3e9c7435771dcafd5000603ae56e37496 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -67,9 +67,9 @@ public: //-- cam_mode enum CameraMode { - CAMERA_MODE_UNDEFINED = -1, - CAMERA_MODE_PHOTO = 0, - CAMERA_MODE_VIDEO = 1, + CAM_MODE_UNDEFINED = -1, + CAM_MODE_PHOTO = 0, + CAM_MODE_VIDEO = 1, }; //-- Video Capture Status diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc index f0a8d2d6f1dd6cb784fef66f9132a2bcef5dcf25..82aef4cff04ef9af359ebb52690d5d9731dc3b62 100644 --- a/src/Camera/QGCCameraIO.cc +++ b/src/Camera/QGCCameraIO.cc @@ -93,7 +93,6 @@ QGCCameraParamIO::_containerRawValueChanged(const QVariant value) void QGCCameraParamIO::_sendParameter() { - qDebug() << "_sendParameter()" << _fact->name(); //-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET mavlink_param_ext_set_t p; mavlink_param_union_t union_value; @@ -139,7 +138,6 @@ QGCCameraParamIO::_sendParameter() &p); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _paramWriteTimer.start(); - qDebug() << "_sendParameter()" << _fact->name() << "sent"; } //----------------------------------------------------------------------------- diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 0a0b683c960ab6dec806a177250bcb92bbd0f7fc..db007e8e4e9c3975fe69883bc4ce9ba740048bdf 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -203,8 +203,7 @@ int Fact::enumIndex(void) } // Current value is not in list, add it manually _metaData->addEnumInfo(QString("Unknown: %1").arg(rawValue().toString()), rawValue()); - emit enumStringsChanged(); - emit enumValuesChanged(); + emit enumsChanged(); return index; } else { qWarning() << kMissingMetadata; diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index b4c189f25e43d8a07db7bacd00a62ac73d1df311..985c68f0b3ec2b6f608bddccc843f8789193a1d3 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -41,9 +41,9 @@ public: Q_PROPERTY(QString defaultValueString READ cookedDefaultValueString CONSTANT) Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) Q_PROPERTY(int enumIndex READ enumIndex WRITE setEnumIndex NOTIFY valueChanged) - Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumStringsChanged) + Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumsChanged) Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged) - Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumValuesChanged) + Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumsChanged) Q_PROPERTY(QString group READ group CONSTANT) Q_PROPERTY(QString longDescription READ longDescription CONSTANT) Q_PROPERTY(QVariant max READ cookedMax CONSTANT) @@ -148,8 +148,7 @@ public: signals: void bitmaskStringsChanged(void); void bitmaskValuesChanged(void); - void enumStringsChanged(void); - void enumValuesChanged(void); + void enumsChanged(void); void sendValueChangedSignalsChanged(bool sendValueChangedSignals); /// QObject Property System signal for value property changes