diff --git a/.appveyor.yml b/.appveyor.yml index 9f981cef85f5faf081695be8f622bdad9eca12f2..22beb1402e63091d60aad79ff8d188c4d11c9ea0 100644 --- a/.appveyor.yml +++ b/.appveyor.yml @@ -15,7 +15,7 @@ environment: install: - git submodule update --init --recursive - call "%ProgramFiles(x86)%\Microsoft Visual Studio 14.0\VC\vcvarsall.bat" x86 - - set PATH=C:\Qt\Tools\QtCreator\bin;C:\Qt\5.9.2\msvc2015\bin;%PATH% + - set PATH=C:\Qt\Tools\QtCreator\bin;C:\Qt\5.9.3\msvc2015\bin;%PATH% - mkdir %LOCALAPPDATA%\QtProject && copy test\qtlogging.ini %LOCALAPPDATA%\QtProject\ - ps: | Write-Host "Installing GStreamer..." -ForegroundColor Cyan @@ -35,7 +35,7 @@ install: Write-Host "Installed" -ForegroundColor Green build_script: - - mkdir %SHADOW_BUILD_DIR% && cd %SHADOW_BUILD_DIR% && C:\Qt\5.9.2\msvc2015\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn %APPVEYOR_BUILD_FOLDER%\qgroundcontrol.pro + - mkdir %SHADOW_BUILD_DIR% && cd %SHADOW_BUILD_DIR% && C:\Qt\5.9.3\msvc2015\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn %APPVEYOR_BUILD_FOLDER%\qgroundcontrol.pro - cd %SHADOW_BUILD_DIR% && jom - if "%CONFIG%" EQU "installer" ( copy %SHADOW_BUILD_DIR%\release\QGroundControl-installer.exe %APPVEYOR_BUILD_FOLDER%\QGroundControl-installer.exe ) # Generate the source server information to embed in the PDB diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index ca491fd27401d7b0745b465b96497d3409bd9eef..d2cfe911cff25310d33e873a5c2c5f8a57eec9a7 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -40,6 +40,7 @@ static const char* kParameterrange = "parameterrange"; static const char* kParameterranges = "parameterranges"; static const char* kParameters = "parameters"; static const char* kReadOnly = "readonly"; +static const char* kWriteOnly = "writeonly"; static const char* kRoption = "roption"; static const char* kStep = "step"; static const char* kStrings = "strings"; @@ -659,6 +660,13 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) //-- Is it read only? bool readOnly = false; read_attribute(parameterNode, kReadOnly, readOnly); + //-- Is it write only? + bool writeOnly = false; + read_attribute(parameterNode, kWriteOnly, writeOnly); + //-- It can't be both + if(readOnly && writeOnly) { + qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName); + } //-- Param type bool unknownType; FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType); @@ -689,6 +697,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) metaData->setLongDescription(description); metaData->setHasControl(control); metaData->setReadOnly(readOnly); + metaData->setWriteOnly(writeOnly); //-- Options (enums) QDomElement optionElem = parameterNode.toElement(); QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions); @@ -797,7 +806,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) metaData->setRawUnits(attr); } } - qCDebug(CameraControlLog) << "New parameter:" << factName; + qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable"); _nameToFactMetaDataMap[factName] = metaData; Fact* pFact = new Fact(_compID, factName, factType, this); QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership); diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc index 577c0207d0d9b70a8f6a6294825bf328edd31749..5f98ff41976989a57f8e57fe4f0c26ce0816d5ba 100644 --- a/src/Camera/QGCCameraIO.cc +++ b/src/Camera/QGCCameraIO.cc @@ -28,8 +28,13 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl _paramWriteTimer.setInterval(3000); _paramRequestTimer.setSingleShot(true); _paramRequestTimer.setInterval(3500); + if(_fact->writeOnly()) { + //-- Write mode is always "done" as it won't ever read + _done = true; + } else { + connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout); + } connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout); - connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout); connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged); connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged); _pMavlink = qgcApp()->toolbox()->mavlinkProtocol(); @@ -38,31 +43,33 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl switch (_fact->type()) { case FactMetaData::valueTypeUint8: case FactMetaData::valueTypeBool: - _mavParamType = MAV_PARAM_TYPE_UINT8; + _mavParamType = MAV_PARAM_EXT_TYPE_UINT8; break; case FactMetaData::valueTypeInt8: - _mavParamType = MAV_PARAM_TYPE_INT8; + _mavParamType = MAV_PARAM_EXT_TYPE_INT8; break; case FactMetaData::valueTypeUint16: - _mavParamType = MAV_PARAM_TYPE_UINT16; + _mavParamType = MAV_PARAM_EXT_TYPE_UINT16; break; case FactMetaData::valueTypeInt16: - _mavParamType = MAV_PARAM_TYPE_INT16; + _mavParamType = MAV_PARAM_EXT_TYPE_INT16; break; case FactMetaData::valueTypeUint32: - _mavParamType = MAV_PARAM_TYPE_UINT32; + _mavParamType = MAV_PARAM_EXT_TYPE_UINT32; break; case FactMetaData::valueTypeFloat: - _mavParamType = MAV_PARAM_TYPE_REAL32; + _mavParamType = MAV_PARAM_EXT_TYPE_REAL32; break; + //-- String and custom are the same for now + case FactMetaData::valueTypeString: case FactMetaData::valueTypeCustom: - _mavParamType = (MAV_PARAM_TYPE)11; // MAV_PARAM_TYPE_CUSTOM; + _mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM; break; default: qWarning() << "Unsupported fact type" << _fact->type() << "for" << _fact->name(); // Fall through case FactMetaData::valueTypeInt32: - _mavParamType = MAV_PARAM_TYPE_INT32; + _mavParamType = MAV_PARAM_EXT_TYPE_INT32; break; } } @@ -71,9 +78,11 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl void QGCCameraParamIO::setParamRequest() { - _paramRequestReceived = false; - _requestRetries = 0; - _paramRequestTimer.start(); + if(!_fact->writeOnly()) { + _paramRequestReceived = false; + _requestRetries = 0; + _paramRequestTimer.start(); + } } //----------------------------------------------------------------------------- @@ -139,6 +148,8 @@ QGCCameraParamIO::_sendParameter() case FactMetaData::valueTypeFloat: union_value.param_float = _fact->rawValue().toFloat(); break; + //-- String and custom are the same for now + case FactMetaData::valueTypeString: case FactMetaData::valueTypeCustom: { QByteArray custom = _fact->rawValue().toByteArray(); @@ -250,28 +261,28 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type) param_ext_union_t u; memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN); switch (param_type) { - case MAV_PARAM_TYPE_REAL32: + case MAV_PARAM_EXT_TYPE_REAL32: var = QVariant(u.param_float); break; - case MAV_PARAM_TYPE_UINT8: + case MAV_PARAM_EXT_TYPE_UINT8: var = QVariant(u.param_uint8); break; - case MAV_PARAM_TYPE_INT8: + case MAV_PARAM_EXT_TYPE_INT8: var = QVariant(u.param_int8); break; - case MAV_PARAM_TYPE_UINT16: + case MAV_PARAM_EXT_TYPE_UINT16: var = QVariant(u.param_uint16); break; - case MAV_PARAM_TYPE_INT16: + case MAV_PARAM_EXT_TYPE_INT16: var = QVariant(u.param_int16); break; - case MAV_PARAM_TYPE_UINT32: + case MAV_PARAM_EXT_TYPE_UINT32: var = QVariant(u.param_uint32); break; - case MAV_PARAM_TYPE_INT32: + case MAV_PARAM_EXT_TYPE_INT32: var = QVariant(u.param_int32); break; - case 11: //MAV_PARAM_TYPE_CUSTOM: + case MAV_PARAM_EXT_TYPE_CUSTOM: var = QVariant(QByteArray(value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN)); break; default: @@ -303,6 +314,14 @@ QGCCameraParamIO::_paramRequestTimeout() void QGCCameraParamIO::paramRequest(bool reset) { + //-- If it's write only, we don't request it. + if(_fact->writeOnly()) { + if(!_done) { + _done = true; + _control->_paramDone(); + } + return; + } if(reset) { _requestRetries = 0; _forceUIUpdate = true; diff --git a/src/Camera/QGCCameraIO.h b/src/Camera/QGCCameraIO.h index a3f4d57a2e1a62c14639b29f534fb34875e022b0..0337266340912840fe9c46e79c50b39700ac1dd0 100644 --- a/src/Camera/QGCCameraIO.h +++ b/src/Camera/QGCCameraIO.h @@ -67,7 +67,7 @@ private: QTimer _paramRequestTimer; bool _done; bool _updateOnSet; - MAV_PARAM_TYPE _mavParamType; + MAV_PARAM_EXT_TYPE _mavParamType; MAVLinkProtocol* _pMavlink; bool _forceUIUpdate; }; diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 8930790b2698b8ad44da993a49c841e0b296848a..3afce178fd287c5a40d106ffde28be1d9a1b8c1d 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -663,6 +663,16 @@ bool Fact::readOnly(void) const } } +bool Fact::writeOnly(void) const +{ + if (_metaData) { + return _metaData->writeOnly(); + } else { + qWarning() << kMissingMetadata << name(); + return false; + } +} + bool Fact::volatileValue(void) const { if (_metaData) { diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index 54ccd2214679a7d8528543b0624b4d80657c8679..cc0336ee80de34e289b58ae89fc77d5a51bc86c5 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -71,6 +71,7 @@ public: Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT) Q_PROPERTY(bool hasControl READ hasControl CONSTANT) Q_PROPERTY(bool readOnly READ readOnly CONSTANT) + Q_PROPERTY(bool writeOnly READ writeOnly CONSTANT) Q_PROPERTY(bool volatileValue READ volatileValue CONSTANT) /// Convert and validate value @@ -119,7 +120,8 @@ public: bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; } bool hasControl (void) const; bool readOnly (void) const; - bool volatileValue (void) const; + bool writeOnly (void) const; + bool volatileValue (void) const; /// Returns the values as a string with full 18 digit precision if float/double. QString rawValueStringFullPrecision(void) const; diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 56d06bd64a4a3ac3acb612964740506792763b06..c5b8202a9b6773a7cb6ab7266ef32dc7bbb5df89 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent) , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _writeOnly (false) , _volatile (false) { _category = kDefaultCategory; @@ -116,6 +117,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _writeOnly (false) , _volatile (false) { _category = kDefaultCategory; @@ -145,6 +147,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _writeOnly (false) , _volatile (false) { _category = kDefaultCategory; @@ -178,6 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) _increment = other._increment; _hasControl = other._hasControl; _readOnly = other._readOnly; + _writeOnly = other._writeOnly; _volatile = other._volatile; return *this; } diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 3f5039e4bb03cbae02a0230e497ee97940d315ce..a61a340a02fbeb3545c48845b71ba53ca69fd630 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -104,6 +104,7 @@ public: bool rebootRequired (void) const { return _rebootRequired; } bool hasControl (void) const { return _hasControl; } bool readOnly (void) const { return _readOnly; } + bool writeOnly (void) const { return _writeOnly; } bool volatileValue (void) const { return _volatile; } /// Amount to increment value when used in controls such as spin button or slider with detents. @@ -135,6 +136,7 @@ public: void setIncrement (double increment) { _increment = increment; } void setHasControl (bool bValue) { _hasControl = bValue; } void setReadOnly (bool bValue) { _readOnly = bValue; } + void setWriteOnly (bool bValue) { _writeOnly = bValue; } void setVolatileValue (bool bValue); void setTranslators(Translator rawTranslator, Translator cookedTranslator); @@ -241,6 +243,7 @@ private: double _increment; bool _hasControl; bool _readOnly; + bool _writeOnly; bool _volatile; // Exact conversion constants diff --git a/src/VideoStreaming/VideoStreaming.cc b/src/VideoStreaming/VideoStreaming.cc index b98c4e23e11e7e32bfde131b8ce02447dc21b4b2..d7ec9a912bdc005d34f3e4e7cc7ed7efad88be98 100644 --- a/src/VideoStreaming/VideoStreaming.cc +++ b/src/VideoStreaming/VideoStreaming.cc @@ -155,6 +155,8 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu #else Q_UNUSED(argc); Q_UNUSED(argv); + Q_UNUSED(logpath); + Q_UNUSED(debuglevel); #endif qmlRegisterType ("QGroundControl.QgcQtGStreamer", 1, 0, "VideoItem"); qmlRegisterUncreatableType("QGroundControl.QgcQtGStreamer", 1, 0, "VideoSurface", QLatin1String("VideoSurface from QML is not supported"));