diff --git a/ChangeLog.md b/ChangeLog.md index 775408e972f58d1e3e8024a4f4f7f582f6d17804..4021b91e027b3a329d1b33f796b7c7759dc2eb84 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -9,6 +9,8 @@ Note: This file only contains high level features or important fixes. * Added Airmap integration to QGC * Added ESTIMATOR_STATUS values to new estimatorStatus Vehicle FactGroup. These are now available to display in instrument panel. * Added Chinese and Turkish localization and partial German localization. +* Make Distance to GCS available for display from instrument panel. +* Make Heading to Home available for display from instrument panel. ## 3.4 diff --git a/src/AnalyzeView/GeoTagController.cc b/src/AnalyzeView/GeoTagController.cc index 3f0627deb204b1ce6f5e775e6b62cf435131e488..b255153ae3dd2f6c691a88df05a3842f7948d20d 100644 --- a/src/AnalyzeView/GeoTagController.cc +++ b/src/AnalyzeView/GeoTagController.cc @@ -114,7 +114,7 @@ void GeoTagController::startTagging(void) _setErrorMessage(tr("Save folder not empty")); return; } - foreach(QString dirFile, imageList) + for(QString dirFile: imageList) { if(!saveDirectory.remove(dirFile)) { _setErrorMessage(tr("Couldn't replace the existing images")); diff --git a/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml b/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml index c32cf6fe4956cecbdff71a7474fb201bf151ff05..301005fa29ec9d92e5283ab1d5b0bb4b2d3e89c8 100644 --- a/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml @@ -198,8 +198,17 @@ SetupPage { property var file: _oldFW ? "Sub/bluerov2-3_5.params" : "Sub/bluerov2-3_5_2.params" onClicked : { - console.log(_oldFW) - console.log(_activeVehicle.firmwarePatchVersion) + controller.loadParameters(file) + hideDialog() + } + } + + QGCButton { + width: parent.width + text: "Blue Robotics BlueROV2 Heavy" + property var file: "Sub/bluerov2-heavy-3_5_2.params" + + onClicked : { controller.loadParameters(file) hideDialog() } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 0feb2f33fb877410dfde150a5e4c36727dbd3ee2..4da3426b1da4ff4beb842423b2fadeae32852c96 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -33,7 +33,7 @@ void AutoPilotPlugin::_recalcSetupComplete(void) { bool newSetupComplete = true; - foreach(const QVariant componentVariant, vehicleComponents()) { + for(const QVariant componentVariant: vehicleComponents()) { VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); if (component) { if (!component->setupComplete()) { @@ -61,7 +61,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void) _recalcSetupComplete(); // Connect signals in order to keep setupComplete up to date - foreach(const QVariant componentVariant, vehicleComponents()) { + for(const QVariant componentVariant: vehicleComponents()) { VehicleComponent* component = qobject_cast(qvariant_cast(componentVariant)); if (component) { connect(component, &VehicleComponent::setupCompleteChanged, this, &AutoPilotPlugin::_recalcSetupComplete); diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.h b/src/AutoPilotPlugins/Common/RadioComponentController.h index a152608a26678030d66d150cb6ae8ef0b8f7cfae..e5e94e5aa3417e45c45477d03ef8a7c58dfe9c65 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.h +++ b/src/AutoPilotPlugins/Common/RadioComponentController.h @@ -68,14 +68,14 @@ public: Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged) Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged) - - Q_ENUMS(BindModes) + enum BindModes { DSM2, DSMX7, DSMX8 }; - + Q_ENUM(BindModes) + Q_INVOKABLE void spektrumBindMode(int mode); Q_INVOKABLE void cancelButtonClicked(void); Q_INVOKABLE void skipButtonClicked(void); diff --git a/src/AutoPilotPlugins/PX4/PX4AdvancedFlightModesController.cc b/src/AutoPilotPlugins/PX4/PX4AdvancedFlightModesController.cc index de83f7847d5e03a9f8451a47c2d0f85c8bd5568b..7e803a0dee31403bd5be04dcbe81a30a516982fb 100644 --- a/src/AutoPilotPlugins/PX4/PX4AdvancedFlightModesController.cc +++ b/src/AutoPilotPlugins/PX4/PX4AdvancedFlightModesController.cc @@ -56,9 +56,7 @@ void PX4AdvancedFlightModesController::_init(void) rcMinParam = QString("RC%1_MIN").arg(channel+1); rcMaxParam = QString("RC%1_MAX").arg(channel+1); rcRevParam = QString("RC%1_REV").arg(channel+1); - - QVariant value; - + _rgRCMin[channel] = getParameterFact(FactSystem::defaultComponentId, rcMinParam)->rawValue().toInt(); _rgRCMax[channel] = getParameterFact(FactSystem::defaultComponentId, rcMaxParam)->rawValue().toInt(); @@ -170,7 +168,7 @@ void PX4AdvancedFlightModesController::_validateConfiguration(void) for (int j=0; jrawValue().toInt(); if (channel == 0) { return 0.0; diff --git a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc index c7296609927e41f126cc06b9ed51fc1347b9b4f2..baff6d26d03b906ca9ff56d27710a193b08c30d9 100644 --- a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc +++ b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc @@ -90,7 +90,6 @@ void PX4AirframeLoader::loadAirframeMetaData(void) QString airframeGroup; QString image; - QString errorString; int xmlState = XmlStateNone; while (!xml.atEnd()) { diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index 8e592446077609f00a12cce1c79b65ea7bc527af..0c55459957ca47de9cec24e71fea7bb0a85d4204 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -43,7 +43,6 @@ bool PowerComponent::requiresSetup(void) const bool PowerComponent::setupComplete(void) const { - QVariant cvalue, evalue, nvalue; return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; diff --git a/src/AutoPilotPlugins/PX4/PowerComponentController.cc b/src/AutoPilotPlugins/PX4/PowerComponentController.cc index 9ab268d137614b356ad334bf38fd931c15439ecb..b09393c302b8540cd5bcce33b1d7eb888434d553 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponentController.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponentController.cc @@ -140,7 +140,6 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int return; } - QString busCompletePrefix("bus conf done:"); if (text.startsWith(calCompletePrefix)) { _stopBusConfig(); emit calibrationSuccess(_warningMessages); diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index b6baf9dedbcb7ae12c20e063426e7eeb9d06c218..91eac3280dfdba93d489284caf01eda988fb85ad 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -917,7 +917,7 @@ void QGCCameraControl::_requestAllParameters() { //-- Reset receive list - foreach(QString paramName, _paramIO.keys()) { + for(QString paramName: _paramIO.keys()) { if(_paramIO[paramName]) { _paramIO[paramName]->setParamRequest(); } else { @@ -984,7 +984,7 @@ QGCCameraControl::_updateActiveList() { //-- Clear out excluded parameters based on exclusion rules QStringList exclusionList; - foreach(QGCCameraOptionExclusion* param, _valueExclusions) { + for(QGCCameraOptionExclusion* param: _valueExclusions) { Fact* pFact = getFact(param->param); if(pFact) { QString option = pFact->rawValueString(); @@ -994,7 +994,7 @@ QGCCameraControl::_updateActiveList() } } QStringList active; - foreach(QString key, _settings) { + for(QString key: _settings) { if(!exclusionList.contains(key)) { active.append(key); } @@ -1094,7 +1094,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) QStringList resetList; QStringList updates; //-- Iterate range sets looking for limited ranges - foreach(QGCCameraOptionRange* pRange, _optionRanges) { + for(QGCCameraOptionRange* pRange: _optionRanges) { //-- If this fact or one of its conditions is part of this range set if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) { Fact* pRFact = getFact(pRange->param); //-- This parameter @@ -1115,7 +1115,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) } } //-- Iterate range sets again looking for resets - foreach(QGCCameraOptionRange* pRange, _optionRanges) { + for(QGCCameraOptionRange* pRange: _optionRanges) { if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) { Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change) if(!resetList.contains(pRange->targetParam)) { @@ -1128,7 +1128,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) } } //-- Update limited range set - foreach (Fact* f, rangesSet.keys()) { + for (Fact* f: rangesSet.keys()) { f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants); if(!updates.contains(f->name())) { _paramIO[f->name()]->optNames = rangesSet[f]->optNames; @@ -1139,7 +1139,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) } } //-- Restore full range set - foreach (Fact* f, rangesReset.keys()) { + for (Fact* f: rangesReset.keys()) { f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]); if(!updates.contains(f->name())) { _paramIO[f->name()]->optNames = _originalOptNames[rangesReset[f]]; @@ -1151,7 +1151,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) } //-- Parameter update requests if(_requestUpdates.contains(pFact->name())) { - foreach(QString param, _requestUpdates[pFact->name()]) { + for(QString param: _requestUpdates[pFact->name()]) { if(!_updatesToRequest.contains(param)) { _updatesToRequest << param; } @@ -1166,7 +1166,7 @@ QGCCameraControl::_updateRanges(Fact* pFact) void QGCCameraControl::_requestParamUpdates() { - foreach(QString param, _updatesToRequest) { + for(QString param: _updatesToRequest) { _paramIO[param]->paramRequest(); } _updatesToRequest.clear(); @@ -1358,7 +1358,7 @@ void QGCCameraControl::_processRanges() { //-- After all parameter are loaded, process parameter ranges - foreach(QGCCameraOptionRange* pRange, _optionRanges) { + for(QGCCameraOptionRange* pRange: _optionRanges) { Fact* pRFact = getFact(pRange->targetParam); if(pRFact) { for(int i = 0; i < pRange->optNames.size(); i++) { @@ -1488,7 +1488,7 @@ QGCCameraControl::_dataReady(QByteArray data) void QGCCameraControl::_paramDone() { - foreach(QString param, _paramIO.keys()) { + for(QString param: _paramIO.keys()) { if(!_paramIO[param]->paramDone()) { return; } diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h index c4f93152b4787797b033a07bdd1f39dd498ff436..99bc34beb8d22b671cc9d26300d961654c4d9397 100644 --- a/src/Camera/QGCCameraControl.h +++ b/src/Camera/QGCCameraControl.h @@ -97,10 +97,10 @@ public: PHOTO_CAPTURE_TIMELAPSE, }; - Q_ENUMS(CameraMode) - Q_ENUMS(VideoStatus) - Q_ENUMS(PhotoStatus) - Q_ENUMS(PhotoMode) + Q_ENUM(CameraMode) + Q_ENUM(VideoStatus) + Q_ENUM(PhotoStatus) + Q_ENUM(PhotoMode) Q_PROPERTY(int version READ version NOTIFY infoChanged) Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 641fe22fe69b591be6024634aff6fd214bbe9648..f45db3070cbaa494148d83909a62f52ff8a787b7 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -221,7 +221,7 @@ int Fact::enumIndex(void) //-- Only enums have an index if(_metaData->enumValues().count()) { int index = 0; - foreach (QVariant enumValue, _metaData->enumValues()) { + for (QVariant enumValue: _metaData->enumValues()) { if (enumValue == rawValue()) { return index; } diff --git a/src/FactSystem/FactGroup.cc b/src/FactSystem/FactGroup.cc index ad11c2400d9d47fccd35b9c084955e613b35e62b..31913205c3faf63efdba52a4bd722bb636742cbf 100644 --- a/src/FactSystem/FactGroup.cc +++ b/src/FactSystem/FactGroup.cc @@ -120,7 +120,7 @@ void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name) void FactGroup::_updateAllValues(void) { - foreach(Fact* fact, _nameToFactMap) { + for(Fact* fact: _nameToFactMap) { fact->sendDeferredValueChangedSignal(); } } diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 0ae8221c6d9f66ea9f7329d33554e5293a75832f..4c088ccd27114e729c3dd5ae969305e75eee5433 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -228,21 +228,21 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString int waitingReadParamNameCount = 0; int waitingWriteParamNameCount = 0; - foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) { + for(int waitingComponentId: _waitingReadParamIndexMap.keys()) { waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count(); } if (waitingReadParamIndexCount) { qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount; } - foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) { + for(int waitingComponentId: _waitingReadParamNameMap.keys()) { waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count(); } if (waitingReadParamNameCount) { qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount; } - foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) { + for(int waitingComponentId: _waitingWriteParamNameMap.keys()) { waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count(); } if (waitingWriteParamNameCount) { @@ -418,7 +418,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) } // Reset index wait lists - foreach (int cid, _paramCountMap.keys()) { + for (int cid: _paramCountMap.keys()) { // Add/Update all indices to the wait list, parameter index is 0-based if(componentId != MAV_COMP_ID_ALL && componentId != cid) continue; @@ -486,7 +486,7 @@ void ParameterManager::refreshParametersPrefix(int componentId, const QString& n componentId = _actualComponentId(componentId); qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")"; - foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) { + for(const QString &name: _mapParameterName2Variant[componentId].keys()) { if (name.startsWith(namePrefix)) { refreshParameter(componentId, name); } @@ -522,7 +522,7 @@ QStringList ParameterManager::parameterNames(int componentId) { QStringList names; - foreach(const QString ¶mName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) { + for(const QString ¶mName: _mapParameterName2Variant[_actualComponentId(componentId)].keys()) { names << paramName; } @@ -534,7 +534,7 @@ void ParameterManager::_setupCategoryMap(void) // Must be able to handle being called multiple times _categoryMap.clear(); - foreach (const QString &name, _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) { + for (const QString &name: _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) { Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value(); _categoryMap[fact->category()][fact->group()] += name; } @@ -564,13 +564,13 @@ bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout) qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to received parameter"; } - foreach(int componentId, _waitingReadParamIndexMap.keys()) { + for(int componentId: _waitingReadParamIndexMap.keys()) { if (_waitingReadParamIndexMap[componentId].count()) { qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count(); qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId]; } - foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) { + for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) { if (_indexBatchQueue.contains(paramIndex)) { // Don't add more than once continue; @@ -629,8 +629,8 @@ void ParameterManager::_waitingParamTimeout(void) _checkInitialLoadComplete(); if (!paramsRequested) { - foreach(int componentId, _waitingWriteParamNameMap.keys()) { - foreach(const QString ¶mName, _waitingWriteParamNameMap[componentId].keys()) { + for(int componentId: _waitingWriteParamNameMap.keys()) { + for(const QString ¶mName: _waitingWriteParamNameMap[componentId].keys()) { paramsRequested = true; _waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { @@ -651,8 +651,8 @@ void ParameterManager::_waitingParamTimeout(void) } if (!paramsRequested) { - foreach(int componentId, _waitingReadParamNameMap.keys()) { - foreach(const QString ¶mName, _waitingReadParamNameMap[componentId].keys()) { + for(int componentId: _waitingReadParamNameMap.keys()) { + for(const QString ¶mName: _waitingReadParamNameMap[componentId].keys()) { paramsRequested = true; _waitingReadParamNameMap[componentId][paramName]++; // Bump retry count if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { @@ -759,7 +759,7 @@ void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId) { CacheMapName2ParamTypeVal cacheMap; - foreach(const QString& name, _mapParameterName2Variant[componentId].keys()) { + for(const QString& name: _mapParameterName2Variant[componentId].keys()) { const Fact *fact = _mapParameterName2Variant[componentId][name].value(); cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue()); } @@ -810,7 +810,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian /* compute the crc of the local cache to check against the remote */ FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin(); - foreach (const QString& name, cacheMap.keys()) { + for (const QString& name: cacheMap.keys()) { bool volatileValue = false; FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType()); @@ -836,7 +836,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian int count = cacheMap.count(); int index = 0; - foreach (const QString& name, cacheMap.keys()) { + for (const QString& name: cacheMap.keys()) { const ParamTypeVal& paramTypeVal = cacheMap[name]; const FactMetaData::ValueType_t fact_type = static_cast(paramTypeVal.first); const int mavType = _factTypeToMavType(fact_type); @@ -868,13 +868,13 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ani->setEndValue(1.0); ani->setDuration(750); - connect(ani, &QVariantAnimation::valueChanged, [this](const QVariant &value) { + connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) { _setLoadProgress(value.toDouble()); }); // Hide 500ms after animation finishes - connect(ani, &QVariantAnimation::finished, [this](){ - QTimer::singleShot(500, [this]() { + connect(ani, &QVariantAnimation::finished, this, [this] { + QTimer::singleShot(500, [this] { _setLoadProgress(0); }); }); @@ -888,7 +888,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) { _debugCacheCRC[componentId] = true; _debugCacheMap[componentId] = cacheMap; - foreach (const QString& name, cacheMap.keys()) { + for (const QString& name: cacheMap.keys()) { _debugCacheParamSeen[componentId][name] = false; } qgcApp()->showMessage(tr("Parameter cache CRC match failed")); @@ -958,8 +958,8 @@ void ParameterManager::writeParametersToStream(QTextStream &stream) stream << "#\n"; stream << "# Vehicle-Id Component-Id Name Value Type\n"; - foreach (int componentId, _mapParameterName2Variant.keys()) { - foreach (const QString ¶mName, _mapParameterName2Variant[componentId].keys()) { + for (int componentId: _mapParameterName2Variant.keys()) { + for (const QString ¶mName: _mapParameterName2Variant[componentId].keys()) { Fact* fact = _mapParameterName2Variant[componentId][paramName].value(); if (fact) { stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n"; @@ -1084,7 +1084,7 @@ void ParameterManager::_addMetaDataToDefaultComponent(void) // Loop over all parameters in default component adding meta data QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()]; - foreach (const QString& key, factMap.keys()) { + for (const QString& key: factMap.keys()) { _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value(), _vehicle->vehicleType()); } } @@ -1096,7 +1096,7 @@ void ParameterManager::_checkInitialLoadComplete(void) return; } - foreach (int componentId, _waitingReadParamIndexMap.keys()) { + for (int componentId: _waitingReadParamIndexMap.keys()) { if (_waitingReadParamIndexMap[componentId].count()) { // We are still waiting on some parameters, not done yet return; @@ -1112,9 +1112,9 @@ void ParameterManager::_checkInitialLoadComplete(void) _initialLoadComplete = true; // Parameter cache crc failure debugging - foreach (int componentId, _debugCacheParamSeen.keys()) { + for (int componentId: _debugCacheParamSeen.keys()) { if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) { - foreach (const QString& paramName, _debugCacheParamSeen[componentId].keys()) { + for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) { if (!_debugCacheParamSeen[componentId][paramName]) { qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName; } @@ -1128,8 +1128,8 @@ void ParameterManager::_checkInitialLoadComplete(void) // Check for index based load failures QString indexList; bool initialLoadFailures = false; - foreach (int componentId, _failedReadParamIndexMap.keys()) { - foreach (int paramIndex, _failedReadParamIndexMap[componentId]) { + for (int componentId: _failedReadParamIndexMap.keys()) { + for (int paramIndex: _failedReadParamIndexMap[componentId]) { if (initialLoadFailures) { indexList += ", "; } diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 945eda943c4b6a84ef8a3424416787a3f2aca459..d00c8fee7a127cf8947bff006f0e36037d74c3be 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -154,7 +154,6 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData return; } - QString errorString; bool badMetaData = true; QStack xmlState; APMFactMetaDataRaw* rawMetaData = NULL; diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 4dcaec8ceaf65f56fb4637c2019ab6af5850d276..a37d040bca29421813c60e361c6ed8792814145e 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -7587,16 +7587,24 @@ to takeoff is reached Maximum number of log directories to keep - If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. + If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. 0 1000 true + + Mission Log + If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). + true + + Disabled + All mission messages + Geotagging messages + + Logging Mode Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. - 0 - 2 true when armed until disarm (default) diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index 702e202502c560823ec8898012e74c70e4319184..4011ed613c01da762552f04b7ed688aebf782cc7 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -66,7 +66,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox) #ifndef QGC_DISABLE_UVC // If we are using a UVC camera setup the device name QList cameras = QCameraInfo::availableCameras(); - foreach (const QCameraInfo &cameraInfo, cameras) { + for (const QCameraInfo &cameraInfo: cameras) { if(cameraInfo.description() == videoSource) { _videoSourceID = cameraInfo.deviceName(); emit videoSourceIDChanged(); diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 65fca29bea461f07dd467063b1966b28f7a9d99d..1da578c5424095dd19db2d90bc214ceb8721884f 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -34,7 +34,7 @@ Map { property string mapName: 'defaultMap' property bool isSatelliteMap: activeMapType.name.indexOf("Satellite") > -1 || activeMapType.name.indexOf("Hybrid") > -1 - property var gcsPosition: QtPositioning.coordinate() + property var gcsPosition: QGroundControl.qgcPositionManger.gcsPosition property bool userPanned: false ///< true: the user has manually panned the map property bool allowGCSLocationCenter: false ///< true: map will center/zoom to gcs location one time property bool allowVehicleLocationCenter: false ///< true: map will center/zoom to vehicle location one time @@ -80,19 +80,12 @@ Map { ExclusiveGroup { id: mapTypeGroup } - // Update ground station position - Connections { - target: QGroundControl.qgcPositionManger - - onLastPositionUpdated: { - if (valid && lastPosition.latitude && Math.abs(lastPosition.latitude) > 0.001 && lastPosition.longitude && Math.abs(lastPosition.longitude) > 0.001) { - gcsPosition = QtPositioning.coordinate(lastPosition.latitude,lastPosition.longitude) - if (!firstGCSPositionReceived && !firstVehiclePositionReceived && allowGCSLocationCenter) { - firstGCSPositionReceived = true - center = gcsPosition - zoomLevel = QGroundControl.flightMapInitialZoom - } - } + // Center map to gcs location + onGcsPositionChanged: { + if (gcsPosition.isValid && allowGCSLocationCenter && !firstGCSPositionReceived && !firstVehiclePositionReceived) { + firstGCSPositionReceived = true + center = gcsPosition + zoomLevel = QGroundControl.flightMapInitialZoom } } diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index 2b1c66f3a07496d2cc2461794dc173fbd513a45c..001418e52edd3a2fc750e3ee4ef4333fb2315e22 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -153,7 +153,7 @@ QVariantList JoystickManager::joysticks(void) { QVariantList list; - foreach (const QString &name, _name2JoystickMap.keys()) { + for (const QString &name: _name2JoystickMap.keys()) { list += QVariant::fromValue(_name2JoystickMap[name]); } diff --git a/src/MissionManager/CameraCalcTest.cc b/src/MissionManager/CameraCalcTest.cc index d6fa3dcb072c512ef877cc84ed38955cacb72589..10571ce12462488110065a867ebcb0ffcea489b2 100644 --- a/src/MissionManager/CameraCalcTest.cc +++ b/src/MissionManager/CameraCalcTest.cc @@ -68,7 +68,7 @@ void CameraCalcTest::_testDirty(void) << _cameraCalc->sideOverlap () << _cameraCalc->adjustedFootprintSide() << _cameraCalc->adjustedFootprintFrontal(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_cameraCalc->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 9b105eaa9dc46095a2425211f51412c352204876..c57b2a028aad2c3c50faa8587eac47e1de3ac0b5 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -33,8 +33,8 @@ public: TakeVideo, StopTakingVideo, TakePhoto - }; - Q_ENUMS(CameraAction) + }; + Q_ENUM(CameraAction) Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged) Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 81225f4e5150b72643d3f819526022001e52a082..a575dff16ed23107d651e041fd7759b21a46feea 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void) QList rgCameraActions; rgCameraActions << CameraSection::TakePhotosIntervalTime << CameraSection::TakePhotoIntervalDistance << CameraSection::StopTakingPhotos << CameraSection::TakeVideo << CameraSection::StopTakingVideo << CameraSection::TakePhoto; - foreach(int cameraAction, rgCameraActions) { + for(int cameraAction: rgCameraActions) { qDebug() << "camera action" << cameraAction; // Reset @@ -1063,8 +1063,8 @@ void CameraSectionTest::_testScanForMultipleItems(void) rgActionItems << _validDistanceItem << _validTimeItem << _validStartVideoItem << _validStopVideoItem << _validTakePhotoItem; // Camera action followed by gimbal/mode - foreach (SimpleMissionItem* actionItem, rgActionItems) { - foreach (SimpleMissionItem* cameraItem, rgCameraItems) { + for (SimpleMissionItem* actionItem: rgActionItems) { + for (SimpleMissionItem* cameraItem: rgCameraItems) { SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); @@ -1084,8 +1084,8 @@ void CameraSectionTest::_testScanForMultipleItems(void) } // Gimbal/Mode followed by camera action - foreach (SimpleMissionItem* actionItem, rgCameraItems) { - foreach (SimpleMissionItem* cameraItem, rgActionItems) { + for (SimpleMissionItem* actionItem: rgCameraItems) { + for (SimpleMissionItem* cameraItem: rgActionItems) { SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index 827ba910ee5d69b253181fe16b62a795c713364e..a0efe3878ee4fcd6aff1827c3307bf702110c998 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList& ite int seqNum = _sequenceNumber; - foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) { + for (const MissionItem* loadedMissionItem: _loadedMissionItems) { MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent); item->setSequenceNumber(seqNum++); items.append(item); @@ -171,11 +171,11 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList& i MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; //qDebug() << "_buildAndAppendMissionItems"; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { bool entryPoint = true; //qDebug() << "start transect"; - foreach (const CoordInfo_t& transectCoordInfo, transect) { + for (const CoordInfo_t& transectCoordInfo: transect) { //qDebug() << transectCoordInfo.coordType; item = new MissionItem(seqNum++, @@ -309,7 +309,7 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void) _surveyAreaPolygon.clear(); QList rgCoord; - foreach (const QGeoCoordinate& vertex, firstSideVertices) { + for (const QGeoCoordinate& vertex: firstSideVertices) { rgCoord.append(vertex); } for (int i=secondSideVertices.count() - 1; i >= 0; i--) { @@ -386,7 +386,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) #if 0 qDebug() << "transect debug"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, transect) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: transect) { qDebug() << coordInfo.coordType; } #endif @@ -423,7 +423,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) } if (reverseTransects) { QList> reversedTransects; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { reversedTransects.prepend(transect); } _transects = reversedTransects; @@ -431,7 +431,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) if (reverseVertices) { for (int i=0; i<_transects.count(); i++) { QList reversedVertices; - foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) { + for (const TransectStyleComplexItem::CoordInfo_t& vertex: _transects[i]) { reversedVertices.prepend(vertex); } _transects[i] = reversedVertices; @@ -466,11 +466,16 @@ void CorridorScanComplexItem::_rebuildTransectsPhase2(void) _complexDistance += _visualTransectPoints[i].value().distanceTo(_visualTransectPoints[i+1].value()); } - if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { - _cameraShots = qCeil(_complexDistance / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble()); + double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(); + if (triggerDistance == 0) { + _cameraShots = 0; } else { - int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble()); - _cameraShots = singleTransectImageCount * _transectCount(); + if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { + _cameraShots = qCeil(_complexDistance / triggerDistance); + } else { + int singleTransectImageCount = qCeil(_corridorPolyline.length() / triggerDistance); + _cameraShots = singleTransectImageCount * _transectCount(); + } } _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value() : QGeoCoordinate(); diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 254790b3da6d49f3a1cb98306c5060ca41e4cc20..5d3733ea1036d9aea7040711f5dc5548ef815af2 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -143,7 +143,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) } QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray(); - foreach (const QJsonValue& jsonPolygonValue, jsonPolygonArray) { + for (const QJsonValue& jsonPolygonValue: jsonPolygonArray) { if (jsonPolygonValue.type() != QJsonValue::Object) { errorString = tr("GeoFence polygon not stored as object"); return false; @@ -157,7 +157,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) } QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray(); - foreach (const QJsonValue& jsonCircleValue, jsonCircleArray) { + for (const QJsonValue& jsonCircleValue: jsonCircleArray) { if (jsonCircleValue.type() != QJsonValue::Object) { errorString = tr("GeoFence circle not stored as object"); return false; diff --git a/src/MissionManager/MissionCommandList.cc b/src/MissionManager/MissionCommandList.cc index 32a9080ac9d4312529dd9c5e33131a6317a748c4..7c0e537e67cd87821644ac98f206d8fcac3e0bd8 100644 --- a/src/MissionManager/MissionCommandList.cc +++ b/src/MissionManager/MissionCommandList.cc @@ -71,7 +71,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b // Iterate over MissionCommandUIInfo objects QJsonArray jsonArray = jsonValue.toArray(); - foreach(QJsonValue info, jsonArray) { + for(QJsonValue info: jsonArray) { if (!info.isObject()) { qWarning() << jsonFilename << "mavCmdArray should contain objects"; return; @@ -96,7 +96,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b } // Build id list - foreach (MAV_CMD id, _infoMap.keys()) { + for (MAV_CMD id: _infoMap.keys()) { _ids << id; } } diff --git a/src/MissionManager/MissionCommandTree.cc b/src/MissionManager/MissionCommandTree.cc index c2db1a1fc6a5520039e0add1597dda6020b6f754..8d4bce9d4c13f13d055f2ab58e166f2a7d1bf04b 100644 --- a/src/MissionManager/MissionCommandTree.cc +++ b/src/MissionManager/MissionCommandTree.cc @@ -47,13 +47,13 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox) } else { #endif // Load all levels of hierarchy - foreach (MAV_AUTOPILOT firmwareType, _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) { + for (MAV_AUTOPILOT firmwareType: _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) { FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR); QList vehicleTypes; vehicleTypes << MAV_TYPE_GENERIC << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE; - foreach(MAV_TYPE vehicleType, vehicleTypes) { + for(MAV_TYPE vehicleType: vehicleTypes) { QString overrideFile = plugin->missionCommandOverrides(vehicleType); if (!overrideFile.isEmpty()) { _staticCommandTree[firmwareType][vehicleType] = new MissionCommandList(overrideFile, firmwareType == MAV_AUTOPILOT_GENERIC && vehicleType == MAV_TYPE_GENERIC /* baseCommandList */, this); @@ -105,7 +105,7 @@ void MissionCommandTree::_collapseHierarchy(Vehicle* _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - foreach (MAV_CMD command, cmdList->commandIds()) { + for (MAV_CMD command: cmdList->commandIds()) { // Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position) if (!qgcApp()->runningUnitTests() && !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty() @@ -238,7 +238,7 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const QVariantList list; QMap commandMap = _availableCommands[baseFirmwareType][baseVehicleType]; - foreach (MAV_CMD command, commandMap.keys()) { + for (MAV_CMD command: commandMap.keys()) { if (command == MAV_CMD_NAV_LAST) { // MAV_CMD_NAV_LAST is used for Mission Settings item. Although we want to be able to get command info for it. // The user should not be able to use it as a command. diff --git a/src/MissionManager/MissionCommandTreeTest.cc b/src/MissionManager/MissionCommandTreeTest.cc index 9407d9f8b6c64d0480a8cede0e64dcd740c3a5e7..4a414fc874e938acfed5574d70dab3e5b6b68542 100644 --- a/src/MissionManager/MissionCommandTreeTest.cc +++ b/src/MissionManager/MissionCommandTreeTest.cc @@ -206,8 +206,8 @@ void MissionCommandTreeTest::testAllTrees(void) vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_QUADROTOR; // This will cause all of the variants of collapsed trees to be built - foreach(MAV_AUTOPILOT firmwareType, firmwareList) { - foreach (MAV_TYPE vehicleType, vehicleList) { + for(MAV_AUTOPILOT firmwareType: firmwareList) { + for (MAV_TYPE vehicleType: vehicleList) { if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_QUADROTOR) { // VTOL in ArduPilot shows up as plane so we can test this pair continue; diff --git a/src/MissionManager/MissionCommandUIInfo.cc b/src/MissionManager/MissionCommandUIInfo.cc index c12b7aaa8c94fa68adc02efa52f630dcafee747c..3c2747d8190b9cc4602d650d8132cfa546613f11 100644 --- a/src/MissionManager/MissionCommandUIInfo.cc +++ b/src/MissionManager/MissionCommandUIInfo.cc @@ -85,7 +85,7 @@ const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommand _infoMap = other._infoMap; _paramRemoveList = other._paramRemoveList; - foreach (int index, other._paramInfoMap.keys()) { + for (int index: other._paramInfoMap.keys()) { _paramInfoMap[index] = new MissionCmdParamInfo(*other._paramInfoMap[index], this); } @@ -167,19 +167,19 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo) { // Override info values - foreach (const QString& valueKey, uiInfo->_infoMap.keys()) { + for (const QString& valueKey: uiInfo->_infoMap.keys()) { _setInfoValue(valueKey, uiInfo->_infoMap[valueKey]); } // Add to the remove params list - foreach (int removeIndex, uiInfo->_paramRemoveList) { + for (int removeIndex: uiInfo->_paramRemoveList) { if (!_paramRemoveList.contains(removeIndex)) { _paramRemoveList.append(removeIndex); } } // Override param info - foreach (const int paramIndex, uiInfo->_paramInfoMap.keys()) { + for (const int paramIndex: uiInfo->_paramInfoMap.keys()) { _paramRemoveList.removeOne(paramIndex); // MissionCmdParamInfo objects are owned by MissionCommandTree are are in existence for the entire run so // we can just use the same pointer reference. @@ -202,7 +202,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ << _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey; // Look for unknown keys in top level object - foreach (const QString& key, jsonObject.keys()) { + for (const QString& key: jsonObject.keys()) { if (!allKeys.contains(key) && key != _commentJsonKey) { errorString = _loadErrorString(QString("Unknown key: %1").arg(key)); return false; @@ -267,7 +267,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } if (jsonObject.contains(_paramRemoveJsonKey)) { QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(",")); - foreach (const QString& indexString, indexList) { + for (const QString& indexString: indexList) { _paramRemoveList.append(indexString.toInt()); } } @@ -308,7 +308,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } QString debugOutput; - foreach (const QString& infoKey, _infoMap.keys()) { + for (const QString& infoKey: _infoMap.keys()) { debugOutput.append(QString("MavCmdInfo %1: %2 ").arg(infoKey).arg(_infoMap[infoKey].toString())); } qCDebug(MissionCommandsLog) << debugOutput; @@ -325,7 +325,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ allParamKeys << _defaultJsonKey << _decimalPlacesJsonKey << _enumStringsJsonKey << _enumValuesJsonKey << _labelJsonKey << _unitsJsonKey << _nanUnchangedJsonKey; // Look for unknown keys in param object - foreach (const QString& key, paramObject.keys()) { + for (const QString& key: paramObject.keys()) { if (!allParamKeys.contains(key) && key != _commentJsonKey) { errorString = _loadErrorString(QString("Unknown param key: %1").arg(key)); return false; @@ -372,7 +372,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ } QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts); - foreach (const QString &enumValue, enumValues) { + for (const QString &enumValue: enumValues) { bool convertOk; double value = enumValue.toDouble(&convertOk); diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 5245141214dc18249333f7d4189a032cc58ef0fe..6f26b67c8566d98c65307b4a705670e654df6f59 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1156,7 +1156,7 @@ void MissionController::_recalcWaypointLines(void) // Create a temporary QObjectList and replace the model data QObjectList objs; objs.reserve(_linesTable.count()); - foreach(CoordinateVector *vect, _linesTable.values()) { + for(CoordinateVector *vect: _linesTable.values()) { objs.append(vect); } diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index f4ed23e4ff9ff3e65d17d9b0385a9ab44548786e..cac8d3bb5b645baedace6e44a127274b972d2001 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -301,7 +301,7 @@ void MissionItemTest::_testLoadFromJsonV1(void) QStringList removeKeys; removeKeys << MissionItem::_jsonParam1Key << MissionItem::_jsonParam2Key << MissionItem::_jsonParam3Key << MissionItem::_jsonParam4Key; - foreach (const QString& removeKey, removeKeys) { + for (const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); @@ -329,7 +329,7 @@ void MissionItemTest::_testLoadFromJsonV2(void) QStringList removeKeys; removeKeys << MissionItem::_jsonCoordinateKey; - foreach(const QString& removeKey, removeKeys) { + for(const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); @@ -399,7 +399,7 @@ void MissionItemTest::_testLoadFromJsonV3(void) MissionItem::_jsonFrameKey << MissionItem::_jsonParamsKey << VisualMissionItem::jsonTypeKey; - foreach(const QString& removeKey, removeKeys) { + for(const QString& removeKey: removeKeys) { QJsonObject badObject = jsonObject; badObject.remove(removeKey); QCOMPARE(missionItem.load(badObject, _seq, errorString), false); diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index a30c4cc91bf20dec391013bcf3c522f2aaca2e6f..833c2f262f128028bbbe5dea2b8b344e2f2a34fe 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -114,7 +114,7 @@ void PlanManager::_writeMissionCount(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _writeMissionItems.count(), _planType); @@ -157,7 +157,7 @@ void PlanManager::_requestList(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _planType); _vehicle->sendMessageOnLink(_dedicatedLink, message); @@ -296,7 +296,7 @@ void PlanManager::_readTransactionComplete(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, MAV_MISSION_ACCEPTED, _planType); @@ -354,7 +354,7 @@ void PlanManager::_requestNextMissionItem(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _itemIndicesToRead[0], _planType); } else { @@ -363,7 +363,7 @@ void PlanManager::_requestNextMissionItem(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _itemIndicesToRead[0], _planType); } @@ -536,7 +536,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m _dedicatedLink->mavlinkChannel(), &messageOut, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, missionRequest.seq, item->frame(), item->command(), @@ -556,7 +556,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m _dedicatedLink->mavlinkChannel(), &messageOut, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, missionRequest.seq, item->frame(), item->command(), @@ -897,7 +897,7 @@ void PlanManager::_removeAllWorker(void) _dedicatedLink->mavlinkChannel(), &message, _vehicle->id(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _planType); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message); _startAckTimeout(AckMissionClearAll); diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index feec11d0ffb3dfd85d7aef124fc9380b9a8e9454..ba3619a38ba375196d72f4f052cbedb64318a7c6 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other) QVariantList vertices = other.path(); QList rgCoord; - foreach (const QVariant& vertexVar, vertices) { + for (const QVariant& vertexVar: vertices) { rgCoord.append(vertexVar.value()); } appendVertices(rgCoord); @@ -162,7 +162,7 @@ void QGCMapPolygon::setPath(const QList& path) { _polygonPath.clear(); _polygonModel.clearAndDeleteContents(); - foreach(const QGeoCoordinate& coord, path) { + for(const QGeoCoordinate& coord: path) { _polygonPath.append(QVariant::fromValue(coord)); _polygonModel.append(new QGCQGeoCoordinate(coord, this)); } @@ -265,7 +265,7 @@ void QGCMapPolygon::appendVertices(const QList& coordinates) { QList objects; - foreach (const QGeoCoordinate& coordinate, coordinates) { + for (const QGeoCoordinate& coordinate: coordinates) { objects.append(new QGCQGeoCoordinate(coordinate, this)); _polygonPath.append(QVariant::fromValue(coordinate)); } diff --git a/src/MissionManager/QGCMapPolyline.cc b/src/MissionManager/QGCMapPolyline.cc index 9d6eda2b93168b5b5500017106cf6065c8cb836d..c4a30859377a10ecb0667f97614792fdefc483c7 100644 --- a/src/MissionManager/QGCMapPolyline.cc +++ b/src/MissionManager/QGCMapPolyline.cc @@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList& path) { _polylinePath.clear(); _polylineModel.clearAndDeleteContents(); - foreach (const QGeoCoordinate& coord, path) { + for (const QGeoCoordinate& coord: path) { _polylinePath.append(QVariant::fromValue(coord)); _polylineModel.append(new QGCQGeoCoordinate(coord, this)); } @@ -382,7 +382,7 @@ void QGCMapPolyline::appendVertices(const QList& coordinates) { QList objects; - foreach (const QGeoCoordinate& coordinate, coordinates) { + for (const QGeoCoordinate& coordinate: coordinates) { objects.append(new QGCQGeoCoordinate(coordinate, this)); _polylinePath.append(QVariant::fromValue(coordinate)); } diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 6fb45ca278cccee186015b1eaf18e799b8a71ae2..40ca7d04e159647b2ac9fcd26a325ed04c44e88a 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -250,7 +250,7 @@ void SimpleMissionItem::_setupMetaData(void) enumStrings.clear(); enumValues.clear(); MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree(); - foreach (const MAV_CMD command, commandTree->allCommandIds()) { + for (const MAV_CMD command: commandTree->allCommandIds()) { enumStrings.append(commandTree->rawName(command)); enumValues.append(QVariant((int)command)); } diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc index 8119c157d86340afa8dbe365be3c61a805b3b3c6..b84a1d23215e07dde15a9e1cd34dd7f88d231484 100644 --- a/src/MissionManager/StructureScanComplexItem.cc +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -433,6 +433,12 @@ void StructureScanComplexItem::_rebuildFlightPolygon(void) void StructureScanComplexItem::_recalcCameraShots(void) { + double triggerDistance = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble(); + if (triggerDistance == 0) { + _setCameraShots(0); + return; + } + if (_flightPolygon.count() < 3) { _setCameraShots(0); return; @@ -450,7 +456,7 @@ void StructureScanComplexItem::_recalcCameraShots(void) return; } - int cameraShots = distance / _cameraCalc.adjustedFootprintSide()->rawValue().toDouble(); + int cameraShots = distance / triggerDistance; _setCameraShots(cameraShots * _layersFact.rawValue().toInt()); } diff --git a/src/MissionManager/StructureScanComplexItemTest.cc b/src/MissionManager/StructureScanComplexItemTest.cc index 88352c9add74b678cee083f0a60eb2731c44c574..17fc257bd161740329f1fbfa4e02c6ed376bfdce 100644 --- a/src/MissionManager/StructureScanComplexItemTest.cc +++ b/src/MissionManager/StructureScanComplexItemTest.cc @@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void) // These facts should set dirty when changed QList rgFacts; rgFacts << _structureScanItem->altitude() << _structureScanItem->layers(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_structureScanItem->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 231729529864b172835c35e55fa0a1bbea3a8281..4758bafc033b8c3d82a6f953f9ee1f612612d16c 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList& items, MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { bool entryPoint = true; - foreach (const CoordInfo_t& transectCoordInfo, transect) { + for (const CoordInfo_t& transectCoordInfo: transect) { item = new MissionItem(seqNum++, MAV_CMD_NAV_WAYPOINT, mavFrame, @@ -940,7 +940,7 @@ bool SurveyComplexItem::_buildAndAppendMissionItems(QList& items, firstWaypointTrigger = true; } - foreach (const QList& transect, _transects) { + for (const QList& transect: _transects) { int pointIndex = 0; QGeoCoordinate coord; CameraTriggerCode cameraTrigger; @@ -1182,7 +1182,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) // Convert from NED to Geo QList> transects; - foreach (const QLineF& line, resultLines) { + for (const QLineF& line: resultLines) { QGeoCoordinate coord; QList transect; @@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly) } // Convert to CoordInfo transects and append to _transects - foreach (const QList& transect, transects) { + for (const QList& transect: transects) { QGeoCoordinate coord; QList coordInfoTransect; TransectStyleComplexItem::CoordInfo_t coordInfo; @@ -1289,20 +1289,24 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void) _complexDistance += _visualTransectPoints[i].value().distanceTo(_visualTransectPoints[i+1].value()); } - if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { - _cameraShots = qCeil(_complexDistance / triggerDistance()); - } else { + if (triggerDistance() == 0) { _cameraShots = 0; - foreach (const QList& transect, _transects) { - QGeoCoordinate firstCameraCoord, lastCameraCoord; - if (_hasTurnaround()) { - firstCameraCoord = transect[1].coord; - lastCameraCoord = transect[transect.count() - 2].coord; - } else { - firstCameraCoord = transect.first().coord; - lastCameraCoord = transect.last().coord; + } else { + if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { + _cameraShots = qCeil(_complexDistance / triggerDistance()); + } else { + _cameraShots = 0; + for (const QList& transect: _transects) { + QGeoCoordinate firstCameraCoord, lastCameraCoord; + if (_hasTurnaround()) { + firstCameraCoord = transect[1].coord; + lastCameraCoord = transect[transect.count() - 2].coord; + } else { + firstCameraCoord = transect.first().coord; + lastCameraCoord = transect.last().coord; + } + _cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance()); } - _cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance()); } } @@ -1345,7 +1349,7 @@ void SurveyComplexItem::_appendLoadedMissionItems(QList& items, QO int seqNum = _sequenceNumber; - foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) { + for (const MissionItem* loadedMissionItem: _loadedMissionItems) { MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent); item->setSequenceNumber(seqNum++); items.append(item); diff --git a/src/MissionManager/SurveyComplexItemTest.cc b/src/MissionManager/SurveyComplexItemTest.cc index ca86135c39a8fde26b74062d72b3f47c4d14b686..0666bda98cc7d358eec1de52ebebf4334197bee3 100644 --- a/src/MissionManager/SurveyComplexItemTest.cc +++ b/src/MissionManager/SurveyComplexItemTest.cc @@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void) // These facts should set dirty when changed QList rgFacts; rgFacts << _surveyItem->gridAngle() << _surveyItem->flyAlternateTransects(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_surveyItem->dirty()); if (fact->typeIsBool()) { diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 22126e744a033c0503f846ea29917225835f3bb5..7005d9a5ed0f25062020fdf4eab43c6f38aad69d 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject) QObject* missionItemParent = new QObject(); QList missionItems; appendMissionItems(missionItems, missionItemParent); - foreach (const MissionItem* missionItem, missionItems) { + for (const MissionItem* missionItem: missionItems) { QJsonObject missionItemJsonObject; missionItem->save(missionItemJsonObject); missionItemsJsonArray.append(missionItemJsonObject); @@ -228,7 +228,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& // Load generated mission items _loadedMissionItemsParent = new QObject(this); QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray(); - foreach (const QJsonValue& missionItemJson, missionItemsJsonArray) { + for (const QJsonValue& missionItemJson: missionItemsJsonArray) { MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent); if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) { _loadedMissionItemsParent->deleteLater(); @@ -371,8 +371,8 @@ void TransectStyleComplexItem::_rebuildTransects(void) double top = 0.; // Generate the visuals transect representation _visualTransectPoints.clear(); - foreach (const QList& transect, _transects) { - foreach (const CoordInfo_t& coordInfo, transect) { + for (const QList& transect: _transects) { + for (const CoordInfo_t& coordInfo: transect) { _visualTransectPoints.append(QVariant::fromValue(coordInfo.coord)); double lat = coordInfo.coord.latitude() + 90.0; double lon = coordInfo.coord.longitude() + 180.0; @@ -440,8 +440,8 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) QList transectPoints; - foreach (const QList& transect, _transects) { - foreach (const CoordInfo_t& coordInfo, transect) { + for (const QList& transect: _transects) { + for (const CoordInfo_t& coordInfo: transect) { transectPoints.append(coordInfo.coord); } } @@ -645,7 +645,7 @@ void TransectStyleComplexItem::_adjustForTolerance(QList& transect) #if 0 qDebug() << "_adjustForTolerance"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedPoints) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedPoints) { qDebug() << coordInfo.coordType; } #endif @@ -698,7 +698,7 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList& #if 0 qDebug() << "_addInterstitialTerrainPoints"; - foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedTransect) { + for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedTransect) { qDebug() << coordInfo.coordType; } #endif @@ -723,7 +723,7 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const // We have to determine from transects int itemCount = 0; - foreach (const QList& rgCoordInfo, _transects) { + for (const QList& rgCoordInfo: _transects) { itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1); } diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc index 99caca57866f72acd39a7cc1d466639f979f6baf..97242c6e7882a5bcabf8bc89b099860d64ce7753 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.cc +++ b/src/MissionManager/TransectStyleComplexItemTest.cc @@ -77,7 +77,7 @@ void TransectStyleComplexItemTest::_testDirty(void) << _transectStyleItem->cameraTriggerInTurnAround() << _transectStyleItem->hoverAndCapture() << _transectStyleItem->refly90Degrees(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); QVERIFY(!_transectStyleItem->dirty()); changeFactValue(fact); @@ -102,7 +102,7 @@ void TransectStyleComplexItemTest::_testDirty(void) void TransectStyleComplexItemTest::_setSurveyAreaPolygon(void) { - foreach (const QGeoCoordinate vertex, _polygonVertices) { + for (const QGeoCoordinate vertex: _polygonVertices) { _transectStyleItem->surveyAreaPolygon()->appendVertex(vertex); } } @@ -132,7 +132,7 @@ void TransectStyleComplexItemTest::_testRebuildTransects(void) << _transectStyleItem->refly90Degrees() << _transectStyleItem->cameraCalc()->frontalOverlap() << _transectStyleItem->cameraCalc()->sideOverlap(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); changeFactValue(fact); QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called); @@ -175,7 +175,7 @@ void TransectStyleComplexItemTest::_testDistanceSignalling(void) rgFacts << _transectStyleItem->turnAroundDistance() << _transectStyleItem->hoverAndCapture() << _transectStyleItem->refly90Degrees(); - foreach(Fact* fact, rgFacts) { + for(Fact* fact: rgFacts) { qDebug() << fact->name(); changeFactValue(fact); QVERIFY(_multiSpy->checkSignalsByMask(complexDistanceChangedMask | greatestDistanceToChangedMask)); diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index bf1b07c38d102712956afdd3be336b20d0001b86..442385078e1d019e57ec977bb0b54fe0d3f233fc 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -37,6 +37,9 @@ QGCView { property bool planControlColapsed: false + ///< This property is used to determine dirty state for prompting on QGC shutdown + readonly property bool dirty: _planMasterController.dirty + readonly property int _decimalPlaces: 8 readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth * 0.5 readonly property real _margin: ScreenTools.defaultFontPixelHeight * 0.5 diff --git a/src/PositionManager/PositionManager.cpp b/src/PositionManager/PositionManager.cpp index c3ad173af98fc675bcbdbe02a2a4e41c83ada27f..146749ca34ae0cbc0cc39227dcaaa3d304cee0fc 100644 --- a/src/PositionManager/PositionManager.cpp +++ b/src/PositionManager/PositionManager.cpp @@ -60,7 +60,19 @@ void QGCPositionManager::setNmeaSourceDevice(QIODevice* device) void QGCPositionManager::_positionUpdated(const QGeoPositionInfo &update) { - emit lastPositionUpdated(update.isValid(), QVariant::fromValue(update.coordinate())); + QGeoCoordinate newGCSPosition = QGeoCoordinate(); + + if (update.isValid()) { + // Note that gcsPosition filters out possible crap values + if (qAbs(update.coordinate().latitude()) > 0.001 && qAbs(update.coordinate().longitude()) > 0.001) { + newGCSPosition = update.coordinate(); + } + } + if (newGCSPosition != _gcsPosition) { + _gcsPosition = newGCSPosition; + emit gcsPositionChanged(_gcsPosition); + } + emit positionInfoUpdated(update); } diff --git a/src/PositionManager/PositionManager.h b/src/PositionManager/PositionManager.h index c8fdadd1baec4d319ed39085a873a7c3a1ce6b63..692ae2324e2b71ada38798ca4aaeb0d9717a9778 100644 --- a/src/PositionManager/PositionManager.h +++ b/src/PositionManager/PositionManager.h @@ -25,6 +25,8 @@ public: QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox); ~QGCPositionManager(); + Q_PROPERTY(QGeoCoordinate gcsPosition READ gcsPosition NOTIFY gcsPositionChanged) + enum QGCPositionSource { Simulated, InternalGPS, @@ -32,6 +34,8 @@ public: NmeaGPS }; + QGeoCoordinate gcsPosition(void) { return _gcsPosition; } + void setPositionSource(QGCPositionSource source); int updateInterval() const; @@ -45,13 +49,15 @@ private slots: void _error(QGeoPositionInfoSource::Error positioningError); signals: - void lastPositionUpdated(bool valid, QVariant lastPosition); + void gcsPositionChanged(QGeoCoordinate gcsPosition); void positionInfoUpdated(QGeoPositionInfo update); private: - int _updateInterval; - QGeoPositionInfoSource * _currentSource; - QGeoPositionInfoSource * _defaultSource; - QNmeaPositionInfoSource * _nmeaSource; - QGeoPositionInfoSource * _simulatedSource; + int _updateInterval; + QGeoCoordinate _gcsPosition; + + QGeoPositionInfoSource* _currentSource; + QGeoPositionInfoSource* _defaultSource; + QNmeaPositionInfoSource* _nmeaSource; + QGeoPositionInfoSource* _simulatedSource; }; diff --git a/src/QGCPalette.h b/src/QGCPalette.h index 03a9f04b301e5a54d055b1f63c198799178c136c..83f412bf05be8373c6526262feba7463179a3227 100644 --- a/src/QGCPalette.h +++ b/src/QGCPalette.h @@ -54,8 +54,6 @@ class QGCPalette : public QObject { Q_OBJECT - Q_ENUMS(Theme) - public: enum ColorGroup { ColorGroupDisabled = 0, @@ -68,6 +66,7 @@ public: Dark, cMaxTheme }; + Q_ENUM(Theme) typedef QColor PaletteColorInfo_t[cMaxTheme][cMaxColorGroup]; diff --git a/src/QGCQFileDialog.cc b/src/QGCQFileDialog.cc index 21fa68b034290492e57cf3730a41f41d02e1db3f..cd7aa48b787ce8114e955c6990dd43d482f0421d 100644 --- a/src/QGCQFileDialog.cc +++ b/src/QGCQFileDialog.cc @@ -159,7 +159,7 @@ QString QGCQFileDialog::getSaveFileName( } break; } - return QString(""); + return {}; } } @@ -190,7 +190,7 @@ QString QGCQFileDialog::_getFirstExtensionInFilter(const QString& filter) { return match.captured(0).mid(2); } } - return QString(""); + return {}; } /// @brief Validates and updates the parameters for the file dialog calls diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index f3fb52439170f66f69f0b3f78f85a11d4e178e89..f448c02dc6f5aab8e40c55201fd083e60f92ddb9 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -70,7 +70,7 @@ QStringList ParameterEditorController::searchParameters(const QString& searchTex { QStringList list; - foreach(const QString ¶mName, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { + for(const QString ¶mName: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { if (searchText.isEmpty()) { list += paramName; } else { @@ -168,11 +168,11 @@ void ParameterEditorController::_updateParameters(void) if (searchItems.isEmpty()) { const QMap >& categoryMap = _vehicle->parameterManager()->getCategoryMap(); - foreach (const QString& parameter, categoryMap[_currentCategory][_currentGroup]) { + for (const QString& parameter: categoryMap[_currentCategory][_currentGroup]) { newParameterList.append(_vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter)); } } else { - foreach(const QString ¶meter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { + for(const QString ¶meter: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter); bool matched = true; diff --git a/src/QmlControls/QGCFileDialogController.cc b/src/QmlControls/QGCFileDialogController.cc index 89ead9bb11adbe76b34d8c330c3616d6cca30206..66f94c4e7767d2e1fc97bbad29a90c283dda6c84 100644 --- a/src/QmlControls/QGCFileDialogController.cc +++ b/src/QmlControls/QGCFileDialogController.cc @@ -24,13 +24,13 @@ QStringList QGCFileDialogController::getFiles(const QString& directoryPath, cons QDir fileDir(directoryPath); QStringList infoListExtensions; - foreach (const QString& extension, fileExtensions) { + for (const QString& extension: fileExtensions) { infoListExtensions.append(QStringLiteral("*.%1").arg(extension)); } QFileInfoList fileInfoList = fileDir.entryInfoList(infoListExtensions, QDir::Files, QDir::Name); - foreach (const QFileInfo& fileInfo, fileInfoList) { + for (const QFileInfo& fileInfo: fileInfoList) { qCDebug(QGCFileDialogControllerLog) << "getFiles found" << fileInfo.fileName(); files << fileInfo.fileName(); } diff --git a/src/QmlControls/QmlObjectListModel.cc b/src/QmlControls/QmlObjectListModel.cc index 51ad32ed7447119eb7064e92f42cb1c5f2124552..64764a3651c9bf379a5ff71645f6d748246250b6 100644 --- a/src/QmlControls/QmlObjectListModel.cc +++ b/src/QmlControls/QmlObjectListModel.cc @@ -183,7 +183,7 @@ void QmlObjectListModel::insert(int i, QList objects) } int j = i; - foreach (QObject* object, objects) { + for (QObject* object: objects) { QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership); // Look for a dirtyChanged signal on the object @@ -233,7 +233,7 @@ void QmlObjectListModel::setDirty(bool dirty) _dirty = dirty; if (!dirty) { // Need to clear dirty from all children - foreach(QObject* object, _objectList) { + for(QObject* object: _objectList) { if (object->property("dirty").isValid()) { object->setProperty("dirty", false); } diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index e916217f4fb8862efc638f3842d7341f6beefb79..4f8437eaae329801834d42ff6c33475a07508dfd 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -435,7 +435,7 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* int y_max = 26 * pow(2, gap) + (2*gap - 1); if ( zoom > 19 ) { - return QString(""); + return {}; } else if ( zoom > 5 && x >= x_min && x <= x_max && y >= y_min && y <= y_max ) { return QString("http://xdworld.vworld.kr:8080/2d/Base/service/%1/%2/%3.png").arg(zoom).arg(x).arg(y); @@ -458,7 +458,7 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* int y_max = 26 * pow(2, gap) + (2*gap - 1); if ( zoom > 19 ) { - return QString(""); + return {}; } else if ( zoom > 5 && x >= x_min && x <= x_max && y >= y_min && y <= y_max ) { return QString("http://xdworld.vworld.kr:8080/2d/Satellite/service/%1/%2/%3.jpeg").arg(zoom).arg(x).arg(y); diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h index 3a5d283d9e0d0e855a6f44e7ef768ceabcbf73cd..7c03166662fd928f7586498f04bfce8f67ce74c6 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h @@ -35,7 +35,7 @@ public: ActionExporting, ActionDone, }; - Q_ENUMS(ImportAction) + Q_ENUM(ImportAction) Q_PROPERTY(int tileX0 READ tileX0 NOTIFY tileX0Changed) Q_PROPERTY(int tileX1 READ tileX1 NOTIFY tileX1Changed) diff --git a/src/QtLocationPlugin/qtlocation/src/location/maps/qgeoserviceprovider.h b/src/QtLocationPlugin/qtlocation/src/location/maps/qgeoserviceprovider.h index ea8c2b6173c0bda4be99ec1323c20e8343f517e0..69a98384719713bb3dab9befdbcc225dd0097815 100644 --- a/src/QtLocationPlugin/qtlocation/src/location/maps/qgeoserviceprovider.h +++ b/src/QtLocationPlugin/qtlocation/src/location/maps/qgeoserviceprovider.h @@ -59,7 +59,7 @@ class QGeoServiceProviderPrivate; class Q_LOCATION_EXPORT QGeoServiceProvider : public QObject { Q_OBJECT - Q_ENUMS(Error) + Q_ENUM(Error) public: enum Error { NoError, diff --git a/src/QtLocationPlugin/qtlocation/src/positioning/qgeoareamonitorsource.h b/src/QtLocationPlugin/qtlocation/src/positioning/qgeoareamonitorsource.h index 4adf06662fd9c338b82228aaa3399368e1e8114c..1d9aa692a54d12b358bc2fb81f91207fb787f0f0 100644 --- a/src/QtLocationPlugin/qtlocation/src/positioning/qgeoareamonitorsource.h +++ b/src/QtLocationPlugin/qtlocation/src/positioning/qgeoareamonitorsource.h @@ -55,7 +55,7 @@ public: UnknownSourceError = 2, NoError = 3 }; - Q_ENUMS(Error) + Q_ENUM(Error) enum AreaMonitorFeature { PersistentAreaMonitorFeature = 0x00000001, diff --git a/src/QtLocationPlugin/qtlocation/src/positioning/qgeopositioninfosource.h b/src/QtLocationPlugin/qtlocation/src/positioning/qgeopositioninfosource.h index bf6f49904e5a92153ac92ea9b69d7f5007865b25..18f2fb0c0228bdf7d44c6ebafa834e1d5928bc38 100644 --- a/src/QtLocationPlugin/qtlocation/src/positioning/qgeopositioninfosource.h +++ b/src/QtLocationPlugin/qtlocation/src/positioning/qgeopositioninfosource.h @@ -54,7 +54,7 @@ public: UnknownSourceError = 2, NoError = 3 }; - Q_ENUMS(Error) + Q_ENUM(Error) enum PositioningMethod { NoPositioningMethods = 0x00000000, diff --git a/src/QtLocationPlugin/qtlocation/src/positioning/qgeosatelliteinfosource.h b/src/QtLocationPlugin/qtlocation/src/positioning/qgeosatelliteinfosource.h index 6066b7d06817f1f5ef1c730bf41c773cf9842daf..07121c73e86bf606e0f279748e8058c5f6bf0fd4 100644 --- a/src/QtLocationPlugin/qtlocation/src/positioning/qgeosatelliteinfosource.h +++ b/src/QtLocationPlugin/qtlocation/src/positioning/qgeosatelliteinfosource.h @@ -54,7 +54,7 @@ public: NoError = 2, UnknownSourceError = -1 }; - Q_ENUMS(Error) + Q_ENUM(Error) explicit QGeoSatelliteInfoSource(QObject *parent); virtual ~QGeoSatelliteInfoSource(); diff --git a/src/QtLocationPlugin/qtlocation/src/positioning/qgeoshape.h b/src/QtLocationPlugin/qtlocation/src/positioning/qgeoshape.h index 32f852b3c5c7a6297f0b1c6b0ffd14d348bd8e2d..23d9de2655c0648f0ceaf8658427f18507faad66 100644 --- a/src/QtLocationPlugin/qtlocation/src/positioning/qgeoshape.h +++ b/src/QtLocationPlugin/qtlocation/src/positioning/qgeoshape.h @@ -48,7 +48,7 @@ class Q_POSITIONING_EXPORT QGeoShape Q_PROPERTY(ShapeType type READ type) Q_PROPERTY(bool isValid READ isValid) Q_PROPERTY(bool isEmpty READ isEmpty) - Q_ENUMS(ShapeType) + Q_ENUM(ShapeType) public: QGeoShape(); diff --git a/src/Settings/UnitsSettings.h b/src/Settings/UnitsSettings.h index 28c3d3dc93a08e15c2a9103dcaa563bc8a6e3c18..84e49e2f0270ea7cd168aef42be948cdbeeeca48 100644 --- a/src/Settings/UnitsSettings.h +++ b/src/Settings/UnitsSettings.h @@ -46,10 +46,10 @@ public: TemperatureUnitsFarenheit, }; - Q_ENUMS(DistanceUnits) - Q_ENUMS(AreaUnits) - Q_ENUMS(SpeedUnits) - Q_ENUMS(TemperatureUnits) + Q_ENUM(DistanceUnits) + Q_ENUM(AreaUnits) + Q_ENUM(SpeedUnits) + Q_ENUM(TemperatureUnits) Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT) Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT) diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index a76d588a2d6dded9d5130cbef798a04c0069cb36..698d7c879307cc36a356079f20cfcf83a8d78c4b 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -71,7 +71,7 @@ VideoSettings::VideoSettings(QObject* parent) #endif #ifndef QGC_DISABLE_UVC QList cameras = QCameraInfo::availableCameras(); - foreach (const QCameraInfo &cameraInfo, cameras) { + for (const QCameraInfo &cameraInfo: cameras) { videoSourceList.append(cameraInfo.description()); } #endif @@ -82,7 +82,7 @@ VideoSettings::VideoSettings(QObject* parent) videoSourceList.insert(0, videoDisabled); } QVariantList videoSourceVarList; - foreach (const QString& videoSource, videoSourceList) { + for (const QString& videoSource: videoSourceList) { videoSourceVarList.append(QVariant::fromValue(videoSource)); } _nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 77074762ecf3ea2ccd219825379d7a0de6b30e91..b2d1dada9cf3c539581f261fc570ba2d46e411f1 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -46,7 +46,7 @@ void TerrainAirMapQuery::requestCoordinateHeights(const QList& c } QString points; - foreach (const QGeoCoordinate& coord, coordinates) { + for (const QGeoCoordinate& coord: coordinates) { points += QString::number(coord.latitude(), 'f', 10) + "," + QString::number(coord.longitude(), 'f', 10) + ","; } @@ -236,7 +236,7 @@ void TerrainAirMapQuery::_parsePathData(const QJsonValue& pathJson) double lonStep = stepArray[1].toDouble(); QList heights; - foreach (const QJsonValue& profileValue, profileArray) { + for (const QJsonValue& profileValue: profileArray) { heights.append(profileValue.toDouble()); } @@ -404,7 +404,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList { error = false; - foreach (const QGeoCoordinate& coordinate, coordinates) { + for (const QGeoCoordinate& coordinate: coordinates) { QString tileHash = _getTileHash(coordinate); qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates hash:coordinate" << tileHash << coordinate; @@ -451,7 +451,7 @@ void TerrainTileManager::_tileFailed(void) { QList noAltitudes; - foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) { + for (const QueuedRequestInfo_t& requestInfo: _requestQueue) { if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) { requestInfo.terrainQueryInterface->_signalCoordinateHeights(false, noAltitudes); } else if (requestInfo.queryMode == QueryMode::QueryModePath) { @@ -584,7 +584,7 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void) // Convert coordinates to point strings for json query QList coords; int requestQueueAdded = 0; - foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) { + for (const QueuedRequestInfo_t& requestInfo: _requestQueue) { SentRequestInfo_t sentRequestInfo = { requestInfo.terrainAtCoordinateQuery, false, requestInfo.coordinates.count() }; _sentRequests.append(sentRequestInfo); coords += requestInfo.coordinates; @@ -604,7 +604,7 @@ void TerrainAtCoordinateBatchManager::_batchFailed(void) { QList noHeights; - foreach (const SentRequestInfo_t& sentRequestInfo, _sentRequests) { + for (const SentRequestInfo_t& sentRequestInfo: _sentRequests) { if (!sentRequestInfo.queryObjectDestroyed) { disconnect(sentRequestInfo.terrainAtCoordinateQuery, &TerrainAtCoordinateQuery::destroyed, this, &TerrainAtCoordinateBatchManager::_queryObjectDestroyed); sentRequestInfo.terrainAtCoordinateQuery->_signalTerrainData(false, noHeights); @@ -663,7 +663,7 @@ void TerrainAtCoordinateBatchManager::_coordinateHeights(bool success, QList path; - foreach (const QVariant& geoVar, polyPath) { + for (const QVariant& geoVar: polyPath) { path.append(geoVar.value()); } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 6fb24bcb393aa10b2729f81ffe5ba7df2c64bc0c..da5b9a208e96d1691f20847845d0a35699d4b87e 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -39,6 +39,7 @@ #include "QGCCameraManager.h" #include "VideoReceiver.h" #include "VideoManager.h" +#include "PositionManager.h" #if defined(QGC_AIRMAP_ENABLED) #include "AirspaceVehicleManager.h" #endif @@ -69,6 +70,8 @@ const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL"; const char* Vehicle::_flightDistanceFactName = "flightDistance"; const char* Vehicle::_flightTimeFactName = "flightTime"; const char* Vehicle::_distanceToHomeFactName = "distanceToHome"; +const char* Vehicle::_headingToHomeFactName = "headingToHome"; +const char* Vehicle::_distanceToGCSFactName = "distanceToGCS"; const char* Vehicle::_hobbsFactName = "hobbs"; const char* Vehicle::_gpsFactGroupName = "gps"; @@ -192,6 +195,8 @@ Vehicle::Vehicle(LinkInterface* link, , _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble) , _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) + , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) + , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _gpsFactGroup(this) , _battery1FactGroup(this) @@ -385,6 +390,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble) , _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) + , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) + , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _gpsFactGroup(this) , _battery1FactGroup(this) @@ -404,10 +411,13 @@ void Vehicle::_commonInit(void) connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged); - connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToHome); - connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceToHome); + connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceHeadingToHome); + connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToGCS); + connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome); connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter); + connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS); + _missionManager = new MissionManager(this); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete); @@ -453,6 +463,8 @@ void Vehicle::_commonInit(void) _addFact(&_flightDistanceFact, _flightDistanceFactName); _addFact(&_flightTimeFact, _flightTimeFactName); _addFact(&_distanceToHomeFact, _distanceToHomeFactName); + _addFact(&_headingToHomeFact, _headingToHomeFactName); + _addFact(&_distanceToGCSFact, _distanceToGCSFactName); _hobbsFact.setRawValue(QVariant(QString("0000:00:00"))); _addFact(&_hobbsFact, _hobbsFactName); @@ -2004,7 +2016,7 @@ bool Vehicle::xConfigMotors(void) QString Vehicle::formatedMessages() { QString messages; - foreach(UASMessage* message, _toolbox->uasMessageHandler()->messages()) { + for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) { messages += message->getFormatedText(); } return messages; @@ -2281,7 +2293,7 @@ QString Vehicle::priorityLinkName(void) const QVariantList Vehicle::links(void) const { QVariantList ret; - foreach( const auto &item, _links ) + for( const auto &item: _links ) ret << QVariant::fromValue(item); return ret; @@ -3589,12 +3601,28 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message) } } -void Vehicle::_updateDistanceToHome(void) +void Vehicle::_updateDistanceHeadingToHome(void) { if (coordinate().isValid() && homePosition().isValid()) { _distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition())); + if (_distanceToHomeFact.rawValue().toDouble() > 1.0) { + _headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition())); + } else { + _headingToHomeFact.setRawValue(qQNaN()); + } } else { _distanceToHomeFact.setRawValue(qQNaN()); + _headingToHomeFact.setRawValue(qQNaN()); + } +} + +void Vehicle::_updateDistanceToGCS(void) +{ + QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition(); + if (coordinate().isValid() && gcsPosition.isValid()) { + _distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition)); + } else { + _distanceToGCSFact.setRawValue(qQNaN()); } } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 38bb64fb777b574282a569328746db4e9a010627..9a1b5da5eeb1c5b639bc405d95d373b601dad350 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -656,6 +656,8 @@ public: Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT) Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT) Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT) + Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT) + Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT) Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) @@ -945,6 +947,8 @@ public: Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; } Fact* flightDistance (void) { return &_flightDistanceFact; } Fact* distanceToHome (void) { return &_distanceToHomeFact; } + Fact* headingToHome (void) { return &_headingToHomeFact; } + Fact* distanceToGCS (void) { return &_distanceToGCSFact; } Fact* hobbs (void) { return &_hobbsFact; } FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; } @@ -1189,7 +1193,8 @@ private slots: void _sendMavCommandAgain(void); void _clearTrajectoryPoints(void); void _clearCameraTriggerPoints(void); - void _updateDistanceToHome(void); + void _updateDistanceHeadingToHome(void); + void _updateDistanceToGCS(void); void _updateHobbsMeter(void); void _vehicleParamLoaded(bool ready); void _sendQGCTimeToVehicle(void); @@ -1453,6 +1458,8 @@ private: Fact _flightDistanceFact; Fact _flightTimeFact; Fact _distanceToHomeFact; + Fact _headingToHomeFact; + Fact _distanceToGCSFact; Fact _hobbsFact; VehicleGPSFactGroup _gpsFactGroup; @@ -1480,6 +1487,8 @@ private: static const char* _flightDistanceFactName; static const char* _flightTimeFactName; static const char* _distanceToHomeFactName; + static const char* _headingToHomeFactName; + static const char* _distanceToGCSFactName; static const char* _hobbsFactName; static const char* _gpsFactGroupName; diff --git a/src/Vehicle/VehicleFact.json b/src/Vehicle/VehicleFact.json index b385571291d9761568ca574c5c22ede9a3b3334c..7adda5a1b68501d00109f7e6e582dc1d7d379318 100644 --- a/src/Vehicle/VehicleFact.json +++ b/src/Vehicle/VehicleFact.json @@ -90,6 +90,20 @@ "decimalPlaces": 1, "units": "m" }, +{ + "name": "headingToHome", + "shortDescription": "Heading to Home", + "type": "double", + "decimalPlaces": 0, + "units": "deg" +}, +{ + "name": "distanceToGCS", + "shortDescription": "Distance to GCS", + "type": "double", + "decimalPlaces": 1, + "units": "m" +}, { "name": "flightTime", "shortDescription": "Flight Time", diff --git a/src/VehicleSetup/Bootloader.cc b/src/VehicleSetup/Bootloader.cc index ec1600acc6c6149282101de2907ed9dda3a4a845..5043caab7662682d93271ffb6a13099d3e97e186 100644 --- a/src/VehicleSetup/Bootloader.cc +++ b/src/VehicleSetup/Bootloader.cc @@ -184,7 +184,7 @@ bool Bootloader::_binProgram(QSerialPort* port, const FirmwareImage* image) { QFile firmwareFile(image->binFilename()); if (!firmwareFile.open(QIODevice::ReadOnly)) { - _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString()); + _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename(), firmwareFile.errorString()); return false; } uint32_t imageSize = (uint32_t)firmwareFile.size(); @@ -354,7 +354,7 @@ bool Bootloader::_binVerifyBytes(QSerialPort* port, const FirmwareImage* image) QFile firmwareFile(image->binFilename()); if (!firmwareFile.open(QIODevice::ReadOnly)) { - _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString()); + _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename(), firmwareFile.errorString()); return false; } uint32_t imageSize = (uint32_t)firmwareFile.size(); @@ -545,7 +545,7 @@ bool Bootloader::open(QSerialPort* port, const QString portName) port->setFlowControl(QSerialPort::NoFlowControl); if (!port->open(QIODevice::ReadWrite)) { - _errorString = tr("Open failed on port %1: %2").arg(portName).arg(port->errorString()); + _errorString = tr("Open failed on port %1: %2").arg(portName, port->errorString()); return false; } diff --git a/src/VehicleSetup/FirmwareImage.cc b/src/VehicleSetup/FirmwareImage.cc index e0fd7b685be77cbed1cb794677fb6ac21aef7851..6306eceb2e14643ac5c5aa3fddc51a98423bb6bc 100644 --- a/src/VehicleSetup/FirmwareImage.cc +++ b/src/VehicleSetup/FirmwareImage.cc @@ -122,7 +122,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename) QFile ihxFile(ihxFilename); if (!ihxFile.open(QIODevice::ReadOnly | QIODevice::Text)) { - emit statusMessage(QString("Unable to open firmware file %1, error: %2").arg(ihxFilename).arg(ihxFile.errorString())); + emit statusMessage(QString("Unable to open firmware file %1, error: %2").arg(ihxFilename, ihxFile.errorString())); return false; } @@ -223,7 +223,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) QFile px4File(imageFilename); if (!px4File.open(QIODevice::ReadOnly | QIODevice::Text)) { - emit statusMessage(tr("Unable to open firmware file %1, error: %2").arg(imageFilename).arg(px4File.errorString())); + emit statusMessage(tr("Unable to open firmware file %1, error: %2").arg(imageFilename, px4File.errorString())); return false; } @@ -292,7 +292,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) parameterFile.close(); } } else { - emit statusMessage(tr("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename).arg(parameterFile.errorString())); + emit statusMessage(tr("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename, parameterFile.errorString())); } // Cache this file with the system @@ -324,7 +324,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) airframeFile.close(); } } else { - emit statusMessage(tr("Unable to open airframe meta data file %1 for writing, error: %2").arg(airframeFilename).arg(airframeFile.errorString())); + emit statusMessage(tr("Unable to open airframe meta data file %1 for writing, error: %2").arg(airframeFilename, airframeFile.errorString())); } } @@ -350,7 +350,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) QFile decompressFile(decompressFilename); if (!decompressFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) { - emit statusMessage(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString())); + emit statusMessage(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename, decompressFile.errorString())); return false; } @@ -449,7 +449,7 @@ bool FirmwareImage::_binLoad(const QString& imageFilename) { QFile binFile(imageFilename); if (!binFile.open(QIODevice::ReadOnly)) { - emit statusMessage(tr("Unabled to open firmware file %1, %2").arg(imageFilename).arg(binFile.errorString())); + emit statusMessage(tr("Unabled to open firmware file %1, %2").arg(imageFilename, binFile.errorString())); return false; } diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index e984f1c0e07fcd457c8eb526e025abc064f0e944..cdbe47729bdfa4000b28ecb7b3368f67b694cd9e 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -354,7 +354,7 @@ void FirmwareUpgradeController::_initFirmwareHash() #endif // PX4 Firmwares - foreach (const FirmwareType_t& firmwareType, px4MapFirmwareTypeToDir.keys()) { + for (const FirmwareType_t& firmwareType: px4MapFirmwareTypeToDir.keys()) { QString dir = px4MapFirmwareTypeToDir[firmwareType]; _rgPX4FMUV5Firmware.insert (FirmwareIdentifier(AutoPilotStackPX4, firmwareType, DefaultVehicleFirmware), px4Url.arg(dir).arg("v5")); _rgPX4FMUV4PROFirmware.insert (FirmwareIdentifier(AutoPilotStackPX4, firmwareType, DefaultVehicleFirmware), px4Url.arg(dir).arg("v4pro")); @@ -365,9 +365,9 @@ void FirmwareUpgradeController::_initFirmwareHash() #if !defined(NO_ARDUPILOT_DIALECT) // ArduPilot Firmwares - foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) { + for (const FirmwareType_t& firmwareType: apmMapFirmwareTypeToDir.keys()) { QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType]; - foreach (const FirmwareVehicleType_t& vehicleType, apmMapVehicleTypeToDir.keys()) { + for (const FirmwareVehicleType_t& vehicleType: apmMapVehicleTypeToDir.keys()) { QString vehicleTypeDir = apmMapVehicleTypeToDir[vehicleType]; QString px4Dir = apmMapVehicleTypeToPX4Dir[vehicleType]; QString filename = apmMapVehicleTypeToFilename[vehicleType]; @@ -382,9 +382,9 @@ void FirmwareUpgradeController::_initFirmwareHash() #if !defined(NO_ARDUPILOT_DIALECT) // ArduPilot ChibiOS Firmwares - foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) { + for (const FirmwareType_t& firmwareType: apmMapFirmwareTypeToDir.keys()) { QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType]; - foreach (const FirmwareVehicleType_t& vehicleType, apmChibiOSMapVehicleTypeToDir.keys()) { + for (const FirmwareVehicleType_t& vehicleType: apmChibiOSMapVehicleTypeToDir.keys()) { QString vehicleTypeDir = apmChibiOSMapVehicleTypeToDir[vehicleType]; QString fmuDir = apmChibiOSMapVehicleTypeToFmuDir[vehicleType]; QString filename = apmChibiOSMapVehicleTypeToFilename[vehicleType]; @@ -692,7 +692,7 @@ void FirmwareUpgradeController::_loadAPMVersions(uint32_t bootloaderBoardID) QHash* prgFirmware = _firmwareHashForBoardId(static_cast(bootloaderBoardID)); - foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) { + for (FirmwareIdentifier firmwareId: prgFirmware->keys()) { if (firmwareId.autopilotStackType == AutoPilotStackAPM) { QString versionFile = QFileInfo(prgFirmware->value(firmwareId)).path() + "/git-version.txt"; @@ -733,7 +733,7 @@ void FirmwareUpgradeController::_apmVersionDownloadFinished(QString remoteFile, QHash* prgFirmware = _firmwareHashForBoardId(static_cast(_bootloaderBoardID)); QString remotePath = QFileInfo(remoteFile).path(); - foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) { + for (FirmwareIdentifier firmwareId: prgFirmware->keys()) { if (remotePath == QFileInfo((*prgFirmware)[firmwareId]).path()) { qCDebug(FirmwareUpgradeLog) << "Adding version to map, version:firwmareType:vehicleType" << version << firmwareId.firmwareType << firmwareId.firmwareVehicleType; _apmVersionMap[firmwareId.firmwareType][firmwareId.firmwareVehicleType] = version; @@ -761,7 +761,7 @@ QStringList FirmwareUpgradeController::apmAvailableVersions(void) _apmVehicleTypeFromCurrentVersionList.clear(); - foreach (FirmwareVehicleType_t vehicleType, vehicleTypes) { + for (FirmwareVehicleType_t vehicleType: vehicleTypes) { if (_apmVersionMap[_selectedFirmwareType].contains(vehicleType)) { QString version; diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h index 7b99a86cee51f298f361bb9e173ff2a1d998b117..012aff91aeae7f2b1f53c89da91edcc4cf76c01f 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/VehicleSetup/FirmwareUpgradeController.h @@ -67,9 +67,9 @@ public: DefaultVehicleFirmware } FirmwareVehicleType_t; - Q_ENUMS(AutoPilotStackType_t) - Q_ENUMS(FirmwareType_t) - Q_ENUMS(FirmwareVehicleType_t) + Q_ENUM(AutoPilotStackType_t) + Q_ENUM(FirmwareType_t) + Q_ENUM(FirmwareVehicleType_t) class FirmwareIdentifier { diff --git a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc index d2ee548babc6b54162164b34f213775984513336..5cfcf8dacf746171ecdea36697850644c7143cef 100644 --- a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc +++ b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc @@ -119,7 +119,7 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void) bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType, QString& boardName) { - foreach (QGCSerialPortInfo info, QGCSerialPortInfo::availablePorts()) { + for (QGCSerialPortInfo info: QGCSerialPortInfo::availablePorts()) { info.getBoardInfo(boardType, boardName); qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------"; diff --git a/src/VehicleSetup/VehicleComponent.cc b/src/VehicleSetup/VehicleComponent.cc index 071940bc0f38a233fd58e58f4cd0a4d13dcac81b..3e5f3e3101ac661e2704b5a3dcd7636d4a936db7 100644 --- a/src/VehicleSetup/VehicleComponent.cc +++ b/src/VehicleSetup/VehicleComponent.cc @@ -54,7 +54,7 @@ void VehicleComponent::addSummaryQmlComponent(QQmlContext* context, QQuickItem* void VehicleComponent::setupTriggerSignals(void) { // Watch for changed on trigger list params - foreach (const QString ¶mName, setupCompleteChangedTriggerList()) { + for (const QString ¶mName: setupCompleteChangedTriggerList()) { if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) { Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName); connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h index 2431105ef1b0b13a9e526cfdc018522cea888035..47a1b963459f0036c4f68ecb03768e38e01422be 100644 --- a/src/api/QGCOptions.h +++ b/src/api/QGCOptions.h @@ -146,7 +146,7 @@ public: POS_CENTER_LEFT, POS_BOTTOM_LEFT }; - Q_ENUMS(Pos) + Q_ENUM(Pos) CustomInstrumentWidget(QObject* parent = NULL); Q_PROPERTY(QUrl source READ source CONSTANT) Q_PROPERTY(Pos widgetPosition READ widgetPosition NOTIFY widgetPositionChanged) diff --git a/src/comm/BluetoothLink.cc b/src/comm/BluetoothLink.cc index e6606987fe7c0037c9a2abeb8aa57d5ff6efd831..6d3eb915003d6f5c244c2835bf1f56a071a91957 100644 --- a/src/comm/BluetoothLink.cc +++ b/src/comm/BluetoothLink.cc @@ -340,7 +340,7 @@ void BluetoothConfiguration::deviceDiscovered(QBluetoothDeviceInfo info) qDebug() << "Address: " << info.address().toString(); qDebug() << "Service Classes:" << info.serviceClasses(); QList uuids = info.serviceUuids(); - foreach (QBluetoothUuid uuid, uuids) { + for (QBluetoothUuid uuid: uuids) { qDebug() << "Service UUID: " << uuid.toString(); } #endif @@ -373,7 +373,7 @@ void BluetoothConfiguration::doneScanning() void BluetoothConfiguration::setDevName(const QString &name) { - foreach(const BluetoothData& data, _deviceList) + for(const BluetoothData& data: _deviceList) { if(data.name == name) { @@ -390,7 +390,7 @@ void BluetoothConfiguration::setDevName(const QString &name) QString BluetoothConfiguration::address() { #ifdef __ios__ - return QString(""); + return {}; #else return _device.address; #endif diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h index 8feda594d11c4cc3731a6354f733a6a28923cc30..e4027313b498f80a58ad0137afcfc0e3d5cd10e1 100644 --- a/src/comm/LinkConfiguration.h +++ b/src/comm/LinkConfiguration.h @@ -19,7 +19,6 @@ class LinkInterface; class LinkConfiguration : public QObject { Q_OBJECT - Q_ENUMS(LinkType) public: LinkConfiguration(const QString& name); @@ -63,6 +62,7 @@ public: #endif TypeLast // Last type value (type >= TypeLast == invalid) }; + Q_ENUM(LinkType) /*! * diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 0030c273c233004250d5fc89eb877087ffe62799..753c61532720abab5ceec57d29b88ed9312ffdc3 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -497,7 +497,7 @@ void LinkManager::_updateAutoConnectLinks(void) #endif // Iterate Comm Ports - foreach (QGCSerialPortInfo portInfo, portList) { + for (QGCSerialPortInfo portInfo: portList) { qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------"; qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName(); qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation(); @@ -638,7 +638,7 @@ void LinkManager::_updateAutoConnectLinks(void) } // Now remove all configs that are gone - foreach (LinkConfiguration* pDeleteConfig, _confToDelete) { + for (LinkConfiguration* pDeleteConfig: _confToDelete) { qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name(); if (pDeleteConfig->link()) { disconnectLink(pDeleteConfig->link()); @@ -703,7 +703,7 @@ void LinkManager::_updateSerialPorts() _commPortDisplayList.clear(); #ifndef NO_SERIAL_LINK QList portList = QSerialPortInfo::availablePorts(); - foreach (const QSerialPortInfo &info, portList) + for (const QSerialPortInfo &info: portList) { QString port = info.systemLocation().trimmed(); _commPortList += port; diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index ffebfe6aa33a9ad1449c2f69b609019ad3427fc6..dff9c3c4bb41da9de0adcf17a290873e380b1cbf 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -453,7 +453,7 @@ void MAVLinkProtocol::checkForLostLogFiles(void) QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); //qDebug() << "Orphaned log file count" << fileInfoList.count(); - foreach(const QFileInfo fileInfo, fileInfoList) { + for(const QFileInfo fileInfo: fileInfoList) { //qDebug() << "Orphaned log file" << fileInfo.filePath(); if (fileInfo.size() == 0) { // Delete all zero length files @@ -476,7 +476,7 @@ void MAVLinkProtocol::deleteTempLogFiles(void) QString filter(QString("*.%1").arg(_logFileExtension)); QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); - foreach(const QFileInfo fileInfo, fileInfoList) { + for(const QFileInfo fileInfo: fileInfoList) { QFile::remove(fileInfo.filePath()); } } diff --git a/src/comm/MockLinkMissionItemHandler.cc b/src/comm/MockLinkMissionItemHandler.cc index 672d4dc5da1cbefa595b8de5ef32369497710e3f..179826898889e039d3e2bdb8da0354138d43b3a6 100644 --- a/src/comm/MockLinkMissionItemHandler.cc +++ b/src/comm/MockLinkMissionItemHandler.cc @@ -156,7 +156,7 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message mavlink_message_t responseMsg; mavlink_msg_mission_count_pack_chan(_mockLink->vehicleId(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _mockLink->mavlinkChannel(), &responseMsg, // Outgoing message msg.sysid, // Target is original sender @@ -224,7 +224,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t& } mavlink_msg_mission_item_pack_chan(_mockLink->vehicleId(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _mockLink->mavlinkChannel(), &responseMsg, // Outgoing message msg.sysid, // Target is original sender @@ -310,7 +310,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber) mavlink_message_t message; mavlink_msg_mission_request_pack_chan(_mockLink->vehicleId(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _mockLink->mavlinkChannel(), &message, _mavlinkProtocol->getSystemId(), @@ -332,7 +332,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) mavlink_message_t message; mavlink_msg_mission_ack_pack_chan(_mockLink->vehicleId(), - MAV_COMP_ID_MISSIONPLANNER, + MAV_COMP_ID_AUTOPILOT1, _mockLink->mavlinkChannel(), &message, _mavlinkProtocol->getSystemId(), diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 9bc551ef36046efae7080dc17a90aff6b4afbdc2..5300ad178f0732a5abddd818098b7cb5c6c8c9d0 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -956,7 +956,7 @@ void QGCFlightGearLink::_printFgfsOutput(void) QByteArray byteArray = _fgProcess->readAllStandardOutput(); QStringList strLines = QString(byteArray).split("\n"); - foreach (const QString &line, strLines){ + for (const QString &line: strLines){ qDebug() << line; } } @@ -968,7 +968,7 @@ void QGCFlightGearLink::_printFgfsError(void) QByteArray byteArray = _fgProcess->readAllStandardError(); QStringList strLines = QString(byteArray).split("\n"); - foreach (const QString &line, strLines){ + for (const QString &line: strLines){ qDebug() << line; } } diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index be22be67aba8564463cba61b1a6314c897991c75..3ebd435cab4f9e757829870fa4e315aecf4602f7 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -123,11 +123,11 @@ void QGCJSBSimLink::run() if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR) { - arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); + arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB, rootJSB, script); } else { - arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); + arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB, rootJSB, script); } process->start(processJSB, arguments); @@ -285,23 +285,20 @@ void QGCJSBSimLink::readBytes() if (s > maxLength) std::cerr << __FILE__ << __LINE__ << " UDP datagram overflow, allowed to read less bytes than datagram size" << std::endl; socket->readDatagram(data, maxLength, &sender, &senderPort); - QByteArray b(data, s); - + /* // Print string -// QString state(b); - -// // Parse string -// float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed; -// double lat, lon, alt; -// double vx, vy, vz, xacc, yacc, zacc; - -// // Send updated state -// emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed, -// pitchspeed, yawspeed, lat, lon, alt, -// vx, vy, vz, xacc, yacc, zacc); - + QByteArray b(data, s); + QString state(b); + // Parse string + float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed; + double lat, lon, alt; + double vx, vy, vz, xacc, yacc, zacc; + // Send updated state + emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed, + pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc); + */ // Echo data for debugging purposes std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl; diff --git a/src/comm/QGCSerialPortInfo.cc b/src/comm/QGCSerialPortInfo.cc index 883239e26b1a3ceb8f9d3171cf6b3861ce829812..56e299fe3ce8ede5567f9bf5de461f7e1ded2105 100644 --- a/src/comm/QGCSerialPortInfo.cc +++ b/src/comm/QGCSerialPortInfo.cc @@ -252,7 +252,7 @@ QList QGCSerialPortInfo::availablePorts(void) { QList list; - foreach(QSerialPortInfo portInfo, QSerialPortInfo::availablePorts()) { + for(QSerialPortInfo portInfo: QSerialPortInfo::availablePorts()) { if (!isSystemPort(&portInfo)) { list << *((QGCSerialPortInfo*)&portInfo); } diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 015ec95c4e22539bcba0ab7f5db7844549f83634..dd0ce09db55cf71a5259d031b9543a1ecc0104ae 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -65,7 +65,7 @@ bool SerialLink::_isBootloader() if( portList.count() == 0){ return false; } - foreach (const QSerialPortInfo &info, portList) + for (const QSerialPortInfo &info: portList) { qCDebug(SerialLinkLog) << "PortName : " << info.portName() << "Description : " << info.description(); qCDebug(SerialLinkLog) << "Manufacturer: " << info.manufacturer(); diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index d91cdb145d5b4ed9ff79092a22145264f46505d2..ecb27e2b7c9ca43dd1411bff4ab72626045095f1 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -253,7 +253,6 @@ static QString get_ip_address(const QString& address) if (info.error() == QHostInfo::NoError) { QList hostAddresses = info.addresses(); - QHostAddress address; for (int i = 0; i < hostAddresses.size(); i++) { // Exclude all IPv6 addresses @@ -263,7 +262,7 @@ static QString get_ip_address(const QString& address) } } } - return QString(""); + return {}; } TCPConfiguration::TCPConfiguration(const QString& name) : LinkConfiguration(name) diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index ff42b07f76a8b6580a4faa49b90cd535ea5805d8..58fe36da5341d6ac68115be1ee787ec787acc6d9 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -65,12 +65,12 @@ static QString get_ip_address(const QString& address) } } } - return QString(""); + return {}; } static bool contains_target(const QList list, const QHostAddress& address, quint16 port) { - foreach(UDPCLient* target, list) { + for(UDPCLient* target: list) { if(target->address == address && target->port == port) { return true; } @@ -91,7 +91,7 @@ UDPLink::UDPLink(SharedLinkConfigurationPointer& config) if (!_udpConfig) { qWarning() << "Internal error"; } - foreach (const QHostAddress &address, QNetworkInterface::allAddresses()) { + for (const QHostAddress &address: QNetworkInterface::allAddresses()) { _localAddress.append(QHostAddress(address)); } moveToThread(this); @@ -156,7 +156,7 @@ bool UDPLink::_isIpLocal(const QHostAddress& add) // On Windows, this is a very expensive call only Redmond would know // why. As such, we make it once and keep the list locally. If a new // interface shows up after we start, it won't be on this list. - foreach (const QHostAddress &address, _localAddress) { + for (const QHostAddress &address: _localAddress) { if (address == add) { // This is a local address of the same host return true; @@ -171,14 +171,14 @@ void UDPLink::_writeBytes(const QByteArray data) return; } // Send to all manually targeted systems - foreach(UDPCLient* target, _udpConfig->targetHosts()) { + for(UDPCLient* target: _udpConfig->targetHosts()) { // Skip it if it's part of the session clients below if(!contains_target(_sessionTargets, target->address, target->port)) { _writeDataGram(data, target); } } // Send to all connected systems - foreach(UDPCLient* target, _sessionTargets) { + for(UDPCLient* target: _sessionTargets) { _writeDataGram(data, target); } } @@ -401,7 +401,7 @@ void UDPConfiguration::_copyFrom(LinkConfiguration *source) if (usource) { _localPort = usource->localPort(); _clearTargetHosts(); - foreach(UDPCLient* target, usource->targetHosts()) { + for(UDPCLient* target: usource->targetHosts()) { if(!contains_target(_targetHosts, target->address, target->port)) { UDPCLient* newTarget = new UDPCLient(target); _targetHosts.append(newTarget); diff --git a/src/qgcunittest/MavlinkLogTest.cc b/src/qgcunittest/MavlinkLogTest.cc index 4a66ebf77dd8086bbdb6272a8c6840cf90ea486a..5810cd49c21c89472106215afaf00e1968830ce8 100644 --- a/src/qgcunittest/MavlinkLogTest.cc +++ b/src/qgcunittest/MavlinkLogTest.cc @@ -38,7 +38,7 @@ void MavlinkLogTest::init(void) // Make sure temp directory is clear of mavlink logs QDir tmpDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); QStringList logFiles(tmpDir.entryList(QStringList(QString("*.%1").arg(_logFileExtension)), QDir::Files)); - foreach(const QString &logFile, logFiles) { + for(const QString &logFile: logFiles) { bool success = tmpDir.remove(logFile); Q_UNUSED(success); Q_ASSERT(success); diff --git a/src/qgcunittest/RadioConfigTest.cc b/src/qgcunittest/RadioConfigTest.cc index 8218af029c4cfa0a83b1af55d657e8f6ef66b693..123b7a5b84d7ef9a50d6aaf1e63e0398faae779a 100644 --- a/src/qgcunittest/RadioConfigTest.cc +++ b/src/qgcunittest/RadioConfigTest.cc @@ -207,7 +207,7 @@ void RadioConfigTest::_init(MAV_AUTOPILOT firmwareType) // Find the radio component QObject* vehicleComponent = NULL; - foreach (const QVariant& varVehicleComponent, _autopilot->vehicleComponents()) { + for (const QVariant& varVehicleComponent: _autopilot->vehicleComponents()) { if (firmwareType == MAV_AUTOPILOT_PX4) { PX4RadioComponent* radioComponent = qobject_cast(varVehicleComponent.value()); if (radioComponent) { @@ -370,7 +370,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) QStringList switchList; switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; - foreach (const QString &switchParam, switchList) { + for (const QString &switchParam: switchList) { Q_ASSERT(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); } } diff --git a/src/qgcunittest/UnitTest.cc b/src/qgcunittest/UnitTest.cc index a39b8cd4db99b7f436af89ed4b0179d7224d1c37..545d26536888c2897b7ef26b40c647c70882c2c9 100644 --- a/src/qgcunittest/UnitTest.cc +++ b/src/qgcunittest/UnitTest.cc @@ -81,7 +81,7 @@ int UnitTest::run(QString& singleTest) { int ret = 0; - foreach (QObject* test, _testList()) { + for (QObject* test: _testList()) { if (singleTest.isEmpty() || singleTest == test->objectName()) { QStringList args; args << "*" << "-maxwarnings" << "0"; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 861b59a0b8e61a7526d649a1b2fed1a41b40dd80..399a0bf787d5d000fd0b71b7b372f42c53c1272e 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -181,9 +181,6 @@ void UAS::receiveMessage(mavlink_message_t message) // and we already got one attitude packet if (message.sysid == uasId && (!attitudeStamped || lastAttitude != 0 || message.msgid == MAVLINK_MSG_ID_ATTITUDE)) { - QString uasState; - QString stateDescription; - bool multiComponentSourceDetected = false; bool wrongComponent = false; diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc index c7cc4a0d1940a29057cd589999f5c2c14f24b424..53381f8dd7e0cac3fc83bede9b592a924f05d51b 100644 --- a/src/ui/MAVLinkDecoder.cc +++ b/src/ui/MAVLinkDecoder.cc @@ -236,7 +236,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 char buf[11]; strncpy(buf, debug.name, 10); buf[10] = '\0'; - name = QString("%1.%2").arg(buf).arg(fieldName); + name = QString("%1.%2").arg(buf, fieldName); time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly } else if (msgid == MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY) @@ -246,7 +246,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 char buf[11]; strncpy(buf, debug.name, 10); buf[10] = '\0'; - name = QString("%1.%2").arg(buf).arg(fieldName); + name = QString("%1.%2").arg(buf, fieldName); time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly } else if (msgid == MAVLINK_MSG_ID_DEBUG) @@ -281,7 +281,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 // XXX this is really ugly, but we do not know a better way to do this mavlink_rc_channels_raw_t raw; mavlink_msg_rc_channels_raw_decode(msg, &raw); - name = name.arg(msgInfo->name).arg(fieldName); + name = name.arg(msgInfo->name, fieldName); name.prepend(QString("port%1_").arg(raw.port)); } else if (msgid == MAVLINK_MSG_ID_RC_CHANNELS_SCALED) @@ -289,7 +289,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 // XXX this is really ugly, but we do not know a better way to do this mavlink_rc_channels_scaled_t scaled; mavlink_msg_rc_channels_scaled_decode(msg, &scaled); - name = name.arg(msgInfo->name).arg(fieldName); + name = name.arg(msgInfo->name, fieldName); name.prepend(QString("port%1_").arg(scaled.port)); } else if (msgid == MAVLINK_MSG_ID_SERVO_OUTPUT_RAW) @@ -297,12 +297,12 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 // XXX this is really ugly, but we do not know a better way to do this mavlink_servo_output_raw_t servo; mavlink_msg_servo_output_raw_decode(msg, &servo); - name = name.arg(msgInfo->name).arg(fieldName); + name = name.arg(msgInfo->name, fieldName); name.prepend(QString("port%1_").arg(servo.port)); } else { - name = name.arg(msgInfo->name).arg(fieldName); + name = name.arg(msgInfo->name, fieldName); } if (multiComponentSourceDetected) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 6a6b6110efa53bbc8f7b379b96c4c2a6ab926f52..565761c0d6843c007681d6bbb107b8d4027ebffc 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -347,7 +347,7 @@ bool MainWindow::_createInnerDockWidget(const QString& widgetName) void MainWindow::_hideAllDockWidgets(void) { - foreach(QGCDockWidget* dockWidget, _mapName2DockWidget) { + for(QGCDockWidget* dockWidget: _mapName2DockWidget) { dockWidget->setVisible(false); } } @@ -448,7 +448,7 @@ void MainWindow::_vehicleAdded(Vehicle* vehicle) void MainWindow::_storeCurrentViewState(void) { #ifndef __mobile__ - foreach(QGCDockWidget* dockWidget, _mapName2DockWidget) { + for(QGCDockWidget* dockWidget: _mapName2DockWidget) { dockWidget->saveSettings(); } #endif @@ -482,7 +482,7 @@ void MainWindow::_loadVisibleWidgetsSettings(void) if (!widgets.isEmpty()) { QStringList nameList = widgets.split(","); - foreach (const QString &name, nameList) { + for (const QString &name: nameList) { _showDockWidget(name, true); } } @@ -493,7 +493,7 @@ void MainWindow::_storeVisibleWidgetsSettings(void) QString widgetNames; bool firstWidget = true; - foreach (const QString &name, _mapName2DockWidget.keys()) { + for (const QString &name: _mapName2DockWidget.keys()) { if (_mapName2DockWidget[name]->isVisible()) { if (!firstWidget) { widgetNames += ","; diff --git a/src/ui/MainWindowInner.qml b/src/ui/MainWindowInner.qml index 4a8af1113edf204397dd116f263e5bb7c5655c07..2c9e5819c9cf7e696d789f4cf6e9d08df883a3d1 100644 --- a/src/ui/MainWindowInner.qml +++ b/src/ui/MainWindowInner.qml @@ -164,7 +164,7 @@ Item { onYes: activeConnectionsCloseDialog.check() function check() { - if (planViewLoader.item && planViewLoader.item.syncNeeded) { + if (planViewLoader.item && planViewLoader.item.dirty) { unsavedMissionCloseDialog.open() } else { activeConnectionsCloseDialog.check() diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index b1a05eb3055214d9143385a8d179ef71ee3704c9..ba47d2db17a1e999f880d929031314f89c193137 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -83,7 +83,7 @@ void QGCMAVLinkInspector::rebuildComponentList() { UASInterface* uas = vehicle->uas(); QMap components = uas->getComponents(); - foreach (int id, components.keys()) + for (int id: components.keys()) { QString name = components.value(id); ui->componentComboBox->addItem(name, id); diff --git a/src/ui/QGCUASFileView.cc b/src/ui/QGCUASFileView.cc index 2a57ec5d39bb8220011e2c37923d6840ddd588f8..e2dc5e29a20606c5262660c6e8509958938005fb 100644 --- a/src/ui/QGCUASFileView.cc +++ b/src/ui/QGCUASFileView.cc @@ -227,9 +227,6 @@ Again: } if (childItem) { - // Process this item - QString text = childItem->text(0); - // Move to the next item for processing at this level _walkIndexStack.last() = ++walkIndex;