diff --git a/QGCInstaller.pri b/QGCInstaller.pri index f3ba9bc22fc2e44bdafc4602f9448b595ce52b11..443ca699e8203120edc641b2a367886f73e2772e 100644 --- a/QGCInstaller.pri +++ b/QGCInstaller.pri @@ -26,12 +26,12 @@ installer { # We cd to release directory so we can run macdeployqt without a path to the # qgroundcontrol.app file. If you specify a path to the .app file the symbolic # links to plugins will not be created correctly. - QMAKE_POST_LINK += && mkdir -p $${DESTDIR}/package QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src # macdeploy is missing some relocations once in a while. "Fix" it: QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1 # Create package QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/" + QMAKE_POST_LINK += && mkdir -p $${DESTDIR}/package QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg QMAKE_POST_LINK += && rm /tmp/tmp.dmg } diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index bccb88ec47a45f2df71336303beaf849c5c70df3..ec1cd138437424c3cd39d5cf922375d3b680bf52 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -22,12 +22,9 @@ #include #include -/* types for local parameter cache */ -typedef QPair ParamTypeVal; -typedef QMap CacheMapName2ParamTypeVal; - -QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log") -QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log") +QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log") +QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log") +QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog, "ParameterManagerDebugCacheFailureLog") // Turn on to debug parameter cache crc misses Fact ParameterManager::_defaultFact; @@ -151,6 +148,24 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString return; } + // Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog) + if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) { + if (_debugCacheMap[componentId].contains(parameterName)) { + const ParamTypeVal& cacheParamTypeVal = _debugCacheMap[componentId][parameterName]; + size_t dataSize = FactMetaData::typeToSize(static_cast(cacheParamTypeVal.first)); + const void *cacheData = cacheParamTypeVal.second.constData(); + + const void *vehicleData = value.constData(); + + if (memcmp(cacheData, vehicleData, dataSize)) { + qDebug() << "Cache/Vehicle values differ for name:cache:actual" << parameterName << value << cacheParamTypeVal.second; + } + _debugCacheParamSeen[componentId][parameterName] = true; + } else { + qDebug() << "Parameter missing from cache" << parameterName; + } + } + _initialRequestTimeoutTimer.stop(); _waitingParamTimeoutTimer.stop(); @@ -340,11 +355,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString _setupCategoryMap(); } - if (_prevWaitingWriteParamNameCount != 0 && waitingWriteParamNameCount == 0) { - // If all the writes just finished the vehicle is up to date, so persist. - _saveToEEPROM(); - } - // Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params // which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values // which in turn causes a perf problem with all the param cache updates. @@ -875,22 +885,13 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian _parameterSetMajorVersion = -1; _clearMetaData(); qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath()); - } -} - -void ParameterManager::_saveToEEPROM(void) -{ - if (_saveRequired) { - _saveRequired = false; - if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) { - _vehicle->sendMavCommand(MAV_COMP_ID_ALL, - MAV_CMD_PREFLIGHT_STORAGE, - true, // showError - 1, // Write parameters to EEPROM - -1); // Don't do anything with mission storage - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM"; - } else { - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable"; + if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) { + _debugCacheCRC[componentId] = true; + _debugCacheMap[componentId] = cacheMap; + foreach (const QString& name, cacheMap.keys()) { + _debugCacheParamSeen[componentId][name] = false; + } + qgcApp()->showMessage(tr("Parameter cache CRC match failed")); } } } @@ -1110,6 +1111,18 @@ void ParameterManager::_checkInitialLoadComplete(void) // We aren't waiting for any more initial parameter updates, initial parameter loading is complete _initialLoadComplete = true; + // Parameter cache crc failure debugging + foreach (int componentId, _debugCacheParamSeen.keys()) { + if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) { + foreach (const QString& paramName, _debugCacheParamSeen[componentId].keys()) { + if (!_debugCacheParamSeen[componentId][paramName]) { + qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName; + } + } + } + } + _debugCacheCRC.clear(); + qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete"; // Check for index based load failures @@ -1423,6 +1436,7 @@ void ParameterManager::_loadOfflineEditingParams(void) _setupCategoryMap(); _parametersReady = true; _initialLoadComplete = true; + _debugCacheCRC.clear(); } void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject) diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index d0f45b16fb4259b97ca136c3e9c09d4382f27281..33d14ff8a3aa64a8fcd868f5a327bcfd44089227 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -30,6 +30,7 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log) +Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog) /// Connects to Parameter Manager to load/update Facts class ParameterManager : public QObject @@ -153,7 +154,6 @@ private: MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType); - void _saveToEEPROM(void); void _checkInitialLoadComplete(void); /// First mapping is by component id @@ -175,6 +175,13 @@ private: int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall + typedef QPair ParamTypeVal; + typedef QMap CacheMapName2ParamTypeVal; + + QMap _debugCacheCRC; ///< true: debug cache crc failure + QMap _debugCacheMap; + QMap> _debugCacheParamSeen; + // Wait counts from previous parameter update cycle int _prevWaitingReadParamIndexCount; int _prevWaitingReadParamNameCount; diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 7d95f4053584ab325563590104caeb1a32668702..461020d514b4ac711c733267e08ad7c8a02649e3 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -43,11 +43,10 @@ public: /// Set of optional capabilites which firmware may support typedef enum { SetFlightModeCapability = 1 << 0, ///< FirmwarePlugin::setFlightMode method is supported - MavCmdPreflightStorageCapability = 1 << 1, ///< MAV_CMD_PREFLIGHT_STORAGE is supported - PauseVehicleCapability = 1 << 2, ///< Vehicle supports pausing at current location - GuidedModeCapability = 1 << 3, ///< Vehicle supports guided mode commands - OrbitModeCapability = 1 << 4, ///< Vehicle supports orbit mode - TakeoffVehicleCapability = 1 << 5, ///< Vehicle supports guided takeoff + PauseVehicleCapability = 1 << 1, ///< Vehicle supports pausing at current location + GuidedModeCapability = 1 << 2, ///< Vehicle supports guided mode commands + OrbitModeCapability = 1 << 3, ///< Vehicle supports orbit mode + TakeoffVehicleCapability = 1 << 4, ///< Vehicle supports guided takeoff } FirmwareCapabilities; /// Maps from on parameter name to another diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 8ea457b678810bf189621c5f3364dde3ddef3281..602fc0dfa0bdb39190699ec1860a22b63d883e68 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -227,7 +227,7 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void) bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) { - int available = MavCmdPreflightStorageCapability | SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; + int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; if (vehicle->multiRotor() || vehicle->vtol()) { available |= TakeoffVehicleCapability; } diff --git a/src/FlightDisplay/GuidedActionConfirm.qml b/src/FlightDisplay/GuidedActionConfirm.qml index 36aedb24b15d75e584ac176c09b9cd8ba84d5545..701cf0c18a7d16de26342d564316e9a906668523 100644 --- a/src/FlightDisplay/GuidedActionConfirm.qml +++ b/src/FlightDisplay/GuidedActionConfirm.qml @@ -42,10 +42,28 @@ Rectangle { if (hideTrigger) { hideTrigger = false altitudeSlider.visible = false + visibleTimer.stop() visible = false } } + function show(immediate) { + if (immediate) { + visible = true + } else { + // We delay showing the confirmation for a small amount in order to any other state + // changes to propogate through the system. This way only the final state shows up. + visibleTimer.restart() + } + } + + Timer { + id: visibleTimer + interval: 1000 + repeat: false + onTriggered: visible = true + } + QGCPalette { id: qgcPal } DeadMouseArea { diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 941846659cac41b3afdad78be9986ec16dc992b2..8c5ad1556c59db935c840c158c8e27d9af6f3ccb 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -185,9 +185,11 @@ Item { // Called when an action is about to be executed in order to confirm function confirmAction(actionCode, actionData) { + var showImmediate = true closeAll() confirmDialog.action = actionCode confirmDialog.actionData = actionData + confirmDialog.hideTrigger = true _actionData = actionData switch (actionCode) { case actionArm: @@ -219,6 +221,7 @@ Item { altitudeSlider.visible = true break; case actionStartMission: + showImmediate = false confirmDialog.title = startMissionTitle confirmDialog.message = startMissionMessage confirmDialog.hideTrigger = Qt.binding(function() { return !showStartMission }) @@ -229,11 +232,13 @@ Item { confirmDialog.hideTrigger = true break; case actionContinueMission: + showImmediate = false confirmDialog.title = continueMissionTitle confirmDialog.message = continueMissionMessage confirmDialog.hideTrigger = Qt.binding(function() { return !showContinueMission }) break; case actionResumeMission: + showImmediate = false confirmDialog.title = resumeMissionTitle confirmDialog.message = resumeMissionMessage confirmDialog.hideTrigger = Qt.binding(function() { return !showResumeMission }) @@ -308,7 +313,7 @@ Item { console.warn("Unknown actionCode", actionCode) return } - confirmDialog.visible = true + confirmDialog.show(showImmediate) } // Executes the specified action diff --git a/src/FlightMap/Images/attitudeDial.svg b/src/FlightMap/Images/attitudeDial.svg old mode 100644 new mode 100755 index 1e74c332107021d7d1e2319c22e44d2a03132dc9..470a24a2c66fd95dcd8dcce7449aa1db59f6024c --- a/src/FlightMap/Images/attitudeDial.svg +++ b/src/FlightMap/Images/attitudeDial.svg @@ -1,15 +1,23 @@ - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc index 8c7aeeaf8b3d3aea23e6d6c0e7253c5b652d81c4..3942ef5cc4aadcf6ff0fe9731ccca47774c05ca1 100644 --- a/src/MissionManager/StructureScanComplexItem.cc +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -24,8 +24,6 @@ QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog") const char* StructureScanComplexItem::_altitudeFactName = "Altitude"; const char* StructureScanComplexItem::_structureHeightFactName = "StructureHeight"; const char* StructureScanComplexItem::_layersFactName = "Layers"; -const char* StructureScanComplexItem::_gimbalPitchFactName = "GimbalPitch"; -const char* StructureScanComplexItem::_gimbalYawFactName = "GimbalYaw"; const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan"; const char* StructureScanComplexItem::_jsonCameraCalcKey = "CameraCalc"; @@ -46,8 +44,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa , _cameraCalc (vehicle) , _altitudeFact (0, _altitudeFactName, FactMetaData::valueTypeDouble) , _layersFact (0, _layersFactName, FactMetaData::valueTypeUint32) - , _gimbalPitchFact (0, _gimbalPitchFactName, FactMetaData::valueTypeDouble) - , _gimbalYawFact (0, _gimbalYawFactName, FactMetaData::valueTypeDouble) { _editorQml = "qrc:/qml/StructureScanEditor.qml"; @@ -57,20 +53,14 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa _altitudeFact.setMetaData (_metaDataMap[_altitudeFactName]); _layersFact.setMetaData (_metaDataMap[_layersFactName]); - _gimbalPitchFact.setMetaData(_metaDataMap[_gimbalPitchFactName]); - _gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawFactName]); _altitudeFact.setRawValue (_altitudeFact.rawDefaultValue()); _layersFact.setRawValue (_layersFact.rawDefaultValue()); - _gimbalPitchFact.setRawValue(_gimbalPitchFact.rawDefaultValue()); - _gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue()); _altitudeFact.setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue()); connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); - connect(&_gimbalPitchFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); - connect(&_gimbalYawFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo); connect(&_structureHeightFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo); @@ -89,7 +79,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged); connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon); - connect(&_cameraCalc, &CameraCalc::cameraNameChanged, this, &StructureScanComplexItem::_resetGimbal); connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcCameraShots); connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots); @@ -132,9 +121,9 @@ int StructureScanComplexItem::lastSequenceNumber(void) const { return _sequenceNumber + (_layersFact.rawValue().toInt() * - ((_flightPolygon.count() + 1) + // 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer - 2)) + // Camera trigger start/stop for each layer - 1; // Gimbal control command + ((_flightPolygon.count() + 1) + // 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer + 2)) + // Camera trigger start/stop for each layer + 2; // ROI_WPNEXT_OFFSET and ROI_NONE commands } void StructureScanComplexItem::setDirty(bool dirty) @@ -154,8 +143,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems) saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; - saveObject[_gimbalPitchFactName] = _gimbalPitchFact.rawValue().toDouble(); - saveObject[_gimbalYawFactName] = _gimbalYawFact.rawValue().toDouble(); saveObject[_altitudeFactName] = _altitudeFact.rawValue().toDouble(); saveObject[_structureHeightFactName] = _structureHeightFact.rawValue().toDouble(); saveObject[_jsonAltitudeRelativeKey] = _altitudeRelative; @@ -186,8 +173,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen { VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true }, { QGCMapPolygon::jsonPolygonKey, QJsonValue::Array, true }, - { _gimbalPitchFactName, QJsonValue::Double, true }, - { _gimbalYawFactName, QJsonValue::Double, true }, { _altitudeFactName, QJsonValue::Double, true }, { _structureHeightFactName, QJsonValue::Double, true }, { _jsonAltitudeRelativeKey, QJsonValue::Bool, true }, @@ -220,8 +205,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen return false; } - _gimbalPitchFact.setRawValue(complexObject[_gimbalPitchFactName].toDouble()); - _gimbalYawFact.setRawValue (complexObject[_gimbalYawFactName].toDouble()); _altitudeFact.setRawValue (complexObject[_altitudeFactName].toDouble()); _layersFact.setRawValue (complexObject[_layersFactName].toDouble()); _altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true); @@ -268,13 +251,11 @@ void StructureScanComplexItem::appendMissionItems(QList& items, QO double baseAltitude = _altitudeFact.rawValue().toDouble(); MissionItem* item = new MissionItem(seqNum++, - MAV_CMD_DO_MOUNT_CONTROL, + MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET, MAV_FRAME_MISSION, - _gimbalPitchFact.rawValue().toDouble(), - 0, // Gimbal roll - _gimbalYawFact.rawValue().toDouble(), - 0, 0, 0, // param 4-6 not used - MAV_MOUNT_MODE_MAVLINK_TARGETING, + 0, 0, 0, 0, // param 1-4 not used + 0, 0, // Pitch and Roll stay in standard orientation + 90, // 90 degreee yaw offset to point to structure true, // autoContinue false, // isCurrentItem missionItemParent); @@ -349,6 +330,15 @@ void StructureScanComplexItem::appendMissionItems(QList& items, QO missionItemParent); items.append(item); } + + item = new MissionItem(seqNum++, + MAV_CMD_DO_SET_ROI_NONE, + MAV_FRAME_MISSION, + 0, 0, 0,0, 0, 0, 0, // param 1-7 not used + true, // autoContinue + false, // isCurrentItem + missionItemParent); + items.append(item); } int StructureScanComplexItem::cameraShots(void) const @@ -447,12 +437,6 @@ void StructureScanComplexItem::_recalcCameraShots(void) _setCameraShots(cameraShots * _layersFact.rawValue().toInt()); } -void StructureScanComplexItem::_resetGimbal(void) -{ - _gimbalPitchFact.setCookedValue(0); - _gimbalYawFact.setCookedValue(90); -} - void StructureScanComplexItem::setAltitudeRelative(bool altitudeRelative) { if (altitudeRelative != _altitudeRelative) { diff --git a/src/MissionManager/StructureScanComplexItem.h b/src/MissionManager/StructureScanComplexItem.h index f7faadcac21ca90d97f064cd205972f1e7d6c429..8ebffef5139507c9ce314d745cb550b53b315e4b 100644 --- a/src/MissionManager/StructureScanComplexItem.h +++ b/src/MissionManager/StructureScanComplexItem.h @@ -28,8 +28,6 @@ public: StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT) - Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) - Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT) Q_PROPERTY(Fact* altitude READ altitude CONSTANT) Q_PROPERTY(Fact* structureHeight READ structureHeight CONSTANT) Q_PROPERTY(Fact* layers READ layers CONSTANT) @@ -47,8 +45,6 @@ public: bool altitudeRelative (void) const { return _altitudeRelative; } int cameraShots (void) const; - Fact* gimbalPitch (void) { return &_gimbalPitchFact; } - Fact* gimbalYaw (void) { return &_gimbalYawFact; } double timeBetweenShots (void); QGCMapPolygon* structurePolygon (void) { return &_structurePolygon; } QGCMapPolygon* flightPolygon (void) { return &_flightPolygon; } @@ -111,7 +107,6 @@ private slots: void _updateCoordinateAltitudes (void); void _rebuildFlightPolygon (void); void _recalcCameraShots (void); - void _resetGimbal (void); void _recalcLayerInfo (void); private: @@ -140,14 +135,10 @@ private: Fact _altitudeFact; Fact _structureHeightFact; Fact _layersFact; - Fact _gimbalPitchFact; - Fact _gimbalYawFact; static const char* _altitudeFactName; static const char* _structureHeightFactName; static const char* _layersFactName; - static const char* _gimbalPitchFactName; - static const char* _gimbalYawFactName; static const char* _jsonCameraCalcKey; static const char* _jsonAltitudeRelativeKey; diff --git a/src/MissionManager/StructureScanComplexItemTest.cc b/src/MissionManager/StructureScanComplexItemTest.cc index 9058f1ae93f1ae30dce5a6bd4c0c892ad3fa147c..3a2a4081f5e5cc92294ce09d49df3ed3c706ce12 100644 --- a/src/MissionManager/StructureScanComplexItemTest.cc +++ b/src/MissionManager/StructureScanComplexItemTest.cc @@ -59,7 +59,7 @@ void StructureScanComplexItemTest::_testDirty(void) // These facts should set dirty when changed QList rgFacts; - rgFacts << _structureScanItem->gimbalPitch() << _structureScanItem->gimbalYaw() << _structureScanItem->altitude() << _structureScanItem->layers(); + rgFacts << _structureScanItem->altitude() << _structureScanItem->layers(); foreach(Fact* fact, rgFacts) { qDebug() << fact->name(); QVERIFY(!_structureScanItem->dirty()); @@ -93,8 +93,6 @@ void StructureScanComplexItemTest::_initItem(void) } _structureScanItem->cameraCalc()->setCameraName(CameraCalc::manualCameraName()); - _structureScanItem->gimbalPitch()->setCookedValue(45); - _structureScanItem->gimbalYaw()->setCookedValue(45); _structureScanItem->layers()->setCookedValue(2); _structureScanItem->setDirty(false); @@ -112,8 +110,6 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item) } QCOMPARE(_structureScanItem->cameraCalc()->cameraName() , CameraCalc::manualCameraName()); - QCOMPARE(item->gimbalPitch()->cookedValue().toDouble(), 45.0); - QCOMPARE(item->gimbalYaw()->cookedValue().toDouble(), 45.0); QCOMPARE(item->layers()->cookedValue().toInt(), 2); } @@ -132,17 +128,6 @@ void StructureScanComplexItemTest::_testSaveLoad(void) newItem->deleteLater(); } -void StructureScanComplexItemTest::_testGimbalAngleUpdate(void) -{ - // This sets the item to CameraCalc::CameraSpecNone and non-standard gimbal angles - _initItem(); - - // Switching to a camera specific setup should set gimbal angles to defaults - _structureScanItem->cameraCalc()->setCameraName(CameraCalc::customCameraName()); - QCOMPARE(_structureScanItem->gimbalPitch()->cookedValue().toDouble(), 0.0); - QCOMPARE(_structureScanItem->gimbalYaw()->cookedValue().toDouble(), 90.0); -} - void StructureScanComplexItemTest::_testItemCount(void) { QList items; diff --git a/src/MissionManager/StructureScanComplexItemTest.h b/src/MissionManager/StructureScanComplexItemTest.h index c6c42432b90e050aabb27425af7b5d2b5bf91453..06f5e1b1a3ac2de335b7c9cee033547877749266 100644 --- a/src/MissionManager/StructureScanComplexItemTest.h +++ b/src/MissionManager/StructureScanComplexItemTest.h @@ -27,7 +27,6 @@ protected: private slots: void _testDirty(void); void _testSaveLoad(void); - void _testGimbalAngleUpdate(void); void _testItemCount(void); private: diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h index d2096ea1fe2d3a86b4bbacd0c3e575ca05d15492..307042c77dd03af635e917cfca7a3a8bce214f61 100644 --- a/src/MissionManager/SurveyMissionItem.h +++ b/src/MissionManager/SurveyMissionItem.h @@ -296,7 +296,7 @@ private: static const char* _jsonFixedValueIsAltitudeKey; static const char* _jsonRefly90DegreesKey; - static const int _hoverAndCaptureDelaySeconds = 2; + static const int _hoverAndCaptureDelaySeconds = 4; }; #endif diff --git a/src/PlanView/MissionSettingsEditor.qml b/src/PlanView/MissionSettingsEditor.qml index 544fa893fa6c4013a19b8f1dcfa4407a19695859..9cb6368d55385bac170db72c70ce62c98e2faf6e 100644 --- a/src/PlanView/MissionSettingsEditor.qml +++ b/src/PlanView/MissionSettingsEditor.qml @@ -36,6 +36,7 @@ Rectangle { property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension property var _appSettings: QGroundControl.settingsManager.appSettings property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly + property bool _showCameraSection: !_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI readonly property string _firmwareLabel: qsTr("Firmware") readonly property string _vehicleLabel: qsTr("Vehicle") @@ -91,6 +92,7 @@ Rectangle { CameraSection { id: cameraSection checked: missionItem.cameraSection.settingsSpecified + visible: _showCameraSection } QGCLabel { @@ -100,7 +102,7 @@ Rectangle { wrapMode: Text.WordWrap horizontalAlignment: Text.AlignHCenter font.pointSize: ScreenTools.smallFontPointSize - visible: cameraSection.checked + visible: _showCameraSection && cameraSection.checked } SectionHeader { diff --git a/src/PlanView/StructureScanEditor.qml b/src/PlanView/StructureScanEditor.qml index 9511c5380af205160d4b615200c0153dfde1a722..60079ea9d199c3404d92bd5ebc413f621a01921d 100644 --- a/src/PlanView/StructureScanEditor.qml +++ b/src/PlanView/StructureScanEditor.qml @@ -81,33 +81,6 @@ Rectangle { sideDistanceLabel: qsTr("Trigger Distance") } - GridLayout { - anchors.left: parent.left - anchors.right: parent.right - columnSpacing: ScreenTools.defaultFontPixelWidth / 2 - rowSpacing: 0 - columns: 3 - visible: missionItem.cameraCalc.isManualCamera - - Item { width: 1; height: 1 } - QGCLabel { text: qsTr("Pitch") } - QGCLabel { text: qsTr("Yaw") } - - QGCLabel { - text: qsTr("Gimbal") - Layout.fillWidth: true - } - FactTextField { - fact: missionItem.gimbalPitch - implicitWidth: ScreenTools.defaultFontPixelWidth * 9 - } - - FactTextField { - fact: missionItem.gimbalYaw - implicitWidth: ScreenTools.defaultFontPixelWidth * 9 - } - } - SectionHeader { id: scanHeader text: qsTr("Scan")