diff --git a/resources/calibration/mode1/radioRollLeft.png b/resources/calibration/mode1/radioRollLeft.png index 7fed7e5061d350cbe1555876faa672d45fa7ec13..8f6a931b8f30d3c41b8968f6b399185a16257ef9 100644 Binary files a/resources/calibration/mode1/radioRollLeft.png and b/resources/calibration/mode1/radioRollLeft.png differ diff --git a/resources/calibration/mode1/radioRollRight.png b/resources/calibration/mode1/radioRollRight.png index b532961f3b4baaef14b9352a66f75d5d8823415e..6d805022c4b67156fbda4d69bbb3b5d650ff340f 100644 Binary files a/resources/calibration/mode1/radioRollRight.png and b/resources/calibration/mode1/radioRollRight.png differ diff --git a/src/AnalyzeView/LogDownloadPage.qml b/src/AnalyzeView/LogDownloadPage.qml index bbe5b37979d213eba2881cf3597fb5b3c220d93b..f2b684d630b7da0669ef8367c57394ded5fc4bff 100644 --- a/src/AnalyzeView/LogDownloadPage.qml +++ b/src/AnalyzeView/LogDownloadPage.qml @@ -186,7 +186,7 @@ AnalyzePage { message: qsTr("All log files will be erased permanently. Is this really what you want?") function accept() { - logDownloadPage.hideDialog() + hideDialog() logController.eraseAll() } } diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 6dd9f531db02a6b53be589ba4c7877ac0743db61..688819d42bc4b444c88627734f2e8ce73f61f224 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -237,7 +237,7 @@ FlightMap { myGeoFenceController: _geoFenceController interactive: false planView: false - homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined + homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : QtPositioning.coordinate() } // Rally points on map diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 8c5ad1556c59db935c840c158c8e27d9af6f3ccb..36252a61d6a69878951f3104088cd2ee68641ed5 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -93,25 +93,26 @@ Item { readonly property int actionVtolTransitionToFwdFlight: 20 readonly property int actionVtolTransitionToMRFlight: 21 - property bool showEmergenyStop: !_hideEmergenyStop && _activeVehicle && _vehicleArmed && _vehicleFlying - property bool showArm: _activeVehicle && !_vehicleArmed - property bool showDisarm: _activeVehicle && _vehicleArmed && !_vehicleFlying - property bool showRTL: _activeVehicle && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode - property bool showTakeoff: _activeVehicle && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying - property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode - property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive && !_vehicleFlying - property bool showContinueMission: _activeVehicle && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1) - property bool showPause: _activeVehicle && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused - property bool showChangeAlt: (_activeVehicle && _vehicleFlying) && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive - property bool showOrbit: !_hideOrbit && _activeVehicle && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive - property bool showLandAbort: _activeVehicle && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding - property bool showGotoLocation: _activeVehicle && _vehicleFlying + property bool showEmergenyStop: _guidedActionsEnabled && !_hideEmergenyStop && _vehicleArmed && _vehicleFlying + property bool showArm: _guidedActionsEnabled && !_vehicleArmed + property bool showDisarm: _guidedActionsEnabled && _vehicleArmed && !_vehicleFlying + property bool showRTL: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode + property bool showTakeoff: _guidedActionsEnabled && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying + property bool showLand: _guidedActionsEnabled && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode + property bool showStartMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying + property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1) + property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused + property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive + property bool showOrbit: _guidedActionsEnabled && !_hideOrbit && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive + property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding + property bool showGotoLocation: _guidedActionsEnabled && _vehicleFlying // Note: The 'missionController.visualItems.count - 3' is a hack to not trigger resume mission when a mission ends with an RTL item property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 3) property bool guidedUIVisible: guidedActionConfirm.visible || guidedActionList.visible + property bool _guidedActionsEnabled: (QGroundControl.corePlugin.options.guidedActionsRequireRCRSSI && _activeVehicle) ? _rcRSSIAvailable : _activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property string _flightMode: _activeVehicle ? _activeVehicle.flightMode : "" property bool _missionAvailable: missionController.containsItems @@ -128,6 +129,7 @@ Item { property bool _hideEmergenyStop: !QGroundControl.corePlugin.options.guidedBarShowEmergencyStop property bool _hideOrbit: !QGroundControl.corePlugin.options.guidedBarShowOrbit property bool _vehicleWasFlying: false + property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI < 255 : false /* //Handy code for debugging state problems @@ -193,7 +195,7 @@ Item { _actionData = actionData switch (actionCode) { case actionArm: - if (_vehicleFlying) { + if (_vehicleFlying || !_guidedActionsEnabled) { return } confirmDialog.title = armTitle diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 64980ba51b7d02ae0d6b3455edffd2c8c5d341dd..ce1ec212e80aaf477b92816573e81a128b7aff1c 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -32,14 +32,16 @@ QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog") -const char* GeoFenceController::_jsonFileTypeValue = "GeoFence"; -const char* GeoFenceController::_jsonBreachReturnKey = "breachReturn"; +const char* GeoFenceController::_jsonFileTypeValue = "GeoFence"; +const char* GeoFenceController::_jsonBreachReturnKey = "breachReturn"; +const char* GeoFenceController::_px4ParamCircularFence = "GF_MAX_HOR_DIST"; GeoFenceController::GeoFenceController(PlanMasterController* masterController, QObject* parent) - : PlanElementController(masterController, parent) - , _geoFenceManager(_managerVehicle->geoFenceManager()) - , _dirty(false) - , _itemsRequested(false) + : PlanElementController (masterController, parent) + , _geoFenceManager (_managerVehicle->geoFenceManager()) + , _dirty (false) + , _itemsRequested (false) + , _px4ParamCircularFenceFact(NULL) { connect(&_polygons, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems); connect(&_circles, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems); @@ -86,6 +88,7 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle) if (_managerVehicle) { _geoFenceManager->disconnect(this); _managerVehicle->disconnect(this); + _managerVehicle->parameterManager()->disconnect(this); _managerVehicle = NULL; _geoFenceManager = NULL; } @@ -102,7 +105,10 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle) connect(_geoFenceManager, &GeoFenceManager::removeAllComplete, this, &GeoFenceController::_managerRemoveAllComplete); connect(_geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged); - connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &RallyPointController::supportedChanged); + connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &GeoFenceController::supportedChanged); + + connect(_managerVehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &GeoFenceController::_parametersReady); + _parametersReady(); emit supportedChanged(supported()); _signalAll(); @@ -413,3 +419,30 @@ bool GeoFenceController::supported(void) const { return (_managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) && (_managerVehicle->maxProtoVersion() >= 200); } + +// Hack for PX4 +double GeoFenceController::paramCircularFence(void) +{ + if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) { + return 0; + } + + return _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence)->rawValue().toDouble(); +} + +void GeoFenceController::_parametersReady(void) +{ + if (_px4ParamCircularFenceFact) { + _px4ParamCircularFenceFact->disconnect(this); + _px4ParamCircularFenceFact = NULL; + } + + if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) { + emit paramCircularFenceChanged(); + return; + } + + _px4ParamCircularFenceFact = _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence); + connect(_px4ParamCircularFenceFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + emit paramCircularFenceChanged(); +} diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index dd13cec9256fc0493932468321570935d343fbf4..87b15766ada2c8d5da701d6adb57c633697d03b9 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -34,6 +34,9 @@ public: Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) + // Hack to expose PX4 circular fence controlled by GF_MAX_HOR_DIST + Q_PROPERTY(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged) + /// Add a new inclusion polygon to the fence /// @param topLeft - Top left coordinate or map viewport /// @param topLeft - Bottom right left coordinate or map viewport @@ -55,6 +58,9 @@ public: /// Clears the interactive bit from all fence items Q_INVOKABLE void clearAllInteractive(void); + double paramCircularFence(void); + + // Overrides from PlanElementController bool supported (void) const final; void start (bool editMode) final; void save (QJsonObject& json) final; @@ -80,17 +86,18 @@ signals: void breachReturnPointChanged (QGeoCoordinate breachReturnPoint); void editorQmlChanged (QString editorQml); void loadComplete (void); + void paramCircularFenceChanged (void); private slots: - void _polygonDirtyChanged(bool dirty); - void _setDirty(void); - void _setFenceFromManager(const QList& polygons, - const QList& circles); - void _setReturnPointFromManager(QGeoCoordinate breachReturnPoint); - void _managerLoadComplete(void); - void _updateContainsItems(void); - void _managerSendComplete(bool error); - void _managerRemoveAllComplete(bool error); + void _polygonDirtyChanged (bool dirty); + void _setDirty (void); + void _setFenceFromManager (const QList& polygons, const QList& circles); + void _setReturnPointFromManager (QGeoCoordinate breachReturnPoint); + void _managerLoadComplete (void); + void _updateContainsItems (void); + void _managerSendComplete (bool error); + void _managerRemoveAllComplete (bool error); + void _parametersReady (void); private: void _init(void); @@ -102,9 +109,11 @@ private: QmlObjectListModel _circles; QGeoCoordinate _breachReturnPoint; bool _itemsRequested; + Fact* _px4ParamCircularFenceFact; static const char* _jsonFileTypeValue; static const char* _jsonBreachReturnKey; + static const char* _px4ParamCircularFence; }; #endif diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index ffe29497831e3633b304b467f9985f9f271866b6..473c19e67a0f68cc7eeb299df30f024f67476194 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -70,8 +70,8 @@ signals: protected: PlanMasterController* _masterController; - Vehicle* _controllerVehicle; - Vehicle* _managerVehicle; + Vehicle* _controllerVehicle; ///< Offline controller vehicle + Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none bool _editMode; }; diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h index 2bdef2ad7da0322985b12a0a98556473da50f649..6e618ed5a4cd938b7a24c3f37fd77869db501fda 100644 --- a/src/MissionManager/PlanMasterController.h +++ b/src/MissionManager/PlanMasterController.h @@ -109,8 +109,8 @@ private: void _showPlanFromManagerVehicle(void); MultiVehicleManager* _multiVehicleMgr; - Vehicle* _controllerVehicle; - Vehicle* _managerVehicle; + Vehicle* _controllerVehicle; ///< Offline controller vehicle + Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none bool _editMode; bool _offline; MissionController _missionController; diff --git a/src/PlanView/GeoFenceMapVisuals.qml b/src/PlanView/GeoFenceMapVisuals.qml index 9e41cc65f3555abe0fac680d1254836f2299eb05..79bf2ad1c4966cfd663dec07866ae3c578ab0d35 100644 --- a/src/PlanView/GeoFenceMapVisuals.qml +++ b/src/PlanView/GeoFenceMapVisuals.qml @@ -30,8 +30,16 @@ Item { property var _breachReturnPointComponent property var _mouseAreaComponent + property var _paramCircleFenceComponent property var _polygons: myGeoFenceController.polygons property var _circles: myGeoFenceController.circles + property color _borderColor: "orange" + property int _borderWidthInclusion: 2 + property int _borderWidthExclusion: 0 + property color _interiorColorExclusion: "orange" + property color _interiorColorInclusion: "transparent" + property real _interiorOpacityExclusion: 0.2 + property real _interiorOpacityInclusion: 1 function addPolygon(inclusionPolygon) { // Initial polygon is inset to take 2/3rds space @@ -69,11 +77,14 @@ Item { Component.onCompleted: { _breachReturnPointComponent = breachReturnPointComponent.createObject(map) map.addMapItem(_breachReturnPointComponent) + _paramCircleFenceComponent = paramCircleFenceComponent.createObject(map) + map.addMapItem(_paramCircleFenceComponent) _mouseAreaComponent = mouseAreaComponent.createObject(map) } Component.onDestruction: { _breachReturnPointComponent.destroy() + _paramCircleFenceComponent.destroy() _mouseAreaComponent.destroy() } @@ -94,10 +105,10 @@ Item { delegate : QGCMapPolygonVisuals { mapControl: map mapPolygon: object - borderWidth: object.inclusion ? 2 : 0 - borderColor: "orange" - interiorColor: object.inclusion ? "transparent" : "orange" - interiorOpacity: object.inclusion ? 1: 0.2 + borderWidth: object.inclusion ? _borderWidthInclusion : _borderWidthExclusion + borderColor: _borderColor + interiorColor: object.inclusion ? _interiorColorInclusion : _interiorColorExclusion + interiorOpacity: object.inclusion ? _interiorOpacityInclusion : _interiorOpacityExclusion } } @@ -107,10 +118,29 @@ Item { delegate : QGCMapCircleVisuals { mapControl: map mapCircle: object - borderWidth: object.inclusion ? 2 : 0 - borderColor: "orange" - interiorColor: object.inclusion ? "transparent" : "orange" - interiorOpacity: object.inclusion ? 1: 0.2 + borderWidth: object.inclusion ? _borderWidthInclusion : _borderWidthExclusion + borderColor: _borderColor + interiorColor: object.inclusion ? _interiorColorInclusion : _interiorColorExclusion + interiorOpacity: object.inclusion ? _interiorOpacityInclusion : _interiorOpacityExclusion + } + } + + // Circular geofence specified from parameter + Component { + id: paramCircleFenceComponent + + MapCircle { + color: _interiorColorInclusion + opacity: _interiorOpacityInclusion + border.color: _borderColor + border.width: _borderWidthInclusion + center: homePosition + radius: _radius + visible: homePosition.isValid && _radius > 0 + + property real _radius: myGeoFenceController.paramCircularFence + + on_RadiusChanged: console.log("_radius", _radius, homePosition.isValid, homePosition) } } diff --git a/src/PlanView/StructureScanEditor.qml b/src/PlanView/StructureScanEditor.qml index 60079ea9d199c3404d92bd5ebc413f621a01921d..b9e37c36bf728ea7a3e5c0201d7e4b41fa75a3de 100644 --- a/src/PlanView/StructureScanEditor.qml +++ b/src/PlanView/StructureScanEditor.qml @@ -159,6 +159,9 @@ Rectangle { QGCLabel { text: qsTr("Photo interval") } QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") } + + QGCLabel { text: qsTr("Trigger Distance") } + QGCLabel { text: missionItem.cameraCalc.adjustedFootprintSide.valueString + " " + QGroundControl.appSettingsDistanceUnitsString } } } // Column } // Rectangle diff --git a/src/PlanView/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml index 9f3d3627cc0547e0b768fcd28eee2ce5a8610624..49942e1850e17f72d72c1304e42e3ead653ef087 100644 --- a/src/PlanView/SurveyItemEditor.qml +++ b/src/PlanView/SurveyItemEditor.qml @@ -658,13 +658,13 @@ Rectangle { columnSpacing: ScreenTools.defaultFontPixelWidth visible: statsHeader.checked - QGCLabel { text: qsTr("Survey area") } + QGCLabel { text: qsTr("Survey Area") } QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString } - QGCLabel { text: qsTr("Photo count") } + QGCLabel { text: qsTr("Photo Count") } QGCLabel { text: missionItem.cameraShots } - QGCLabel { text: qsTr("Photo interval") } + QGCLabel { text: qsTr("Photo Interval") } QGCLabel { text: { var timeVal = missionItem.timeBetweenShots @@ -674,6 +674,9 @@ Rectangle { return timeVal.toFixed(1) + " " + qsTr("secs") } } + + QGCLabel { text: qsTr("Trigger Distance") } + QGCLabel { text: missionItem.cameraTriggerDistance.valueString + " " + QGroundControl.appSettingsDistanceUnitsString } } } diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h index 193253cc560b126aa95175861044562d852ca396..b5d6006f64c35e6dd1406dabe3cc157354aba15c 100644 --- a/src/api/QGCCorePlugin.h +++ b/src/api/QGCCorePlugin.h @@ -21,8 +21,6 @@ /// @brief Core Plugin Interface for QGroundControl /// @author Gus Grubba -// Work In Progress - class QGCApplication; class QGCOptions; class QGCSettings; @@ -33,6 +31,7 @@ class QQmlApplicationEngine; class Vehicle; class LinkInterface; class QmlObjectListModel; + class QGCCorePlugin : public QGCTool { Q_OBJECT diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h index a441b0139c5e68d335075d07be7163308e16beb3..107f76cb20aa162baa64f41b0b7faa4bf8777429 100644 --- a/src/api/QGCOptions.h +++ b/src/api/QGCOptions.h @@ -46,6 +46,7 @@ public: Q_PROPERTY(bool showOfflineMapImport READ showOfflineMapImport NOTIFY showOfflineMapImportChanged) Q_PROPERTY(bool useMobileFileDialog READ useMobileFileDialog CONSTANT) Q_PROPERTY(bool showMissionStatus READ showMissionStatus CONSTANT) + Q_PROPERTY(bool guidedActionsRequireRCRSSI READ guidedActionsRequireRCRSSI CONSTANT) /// Should QGC hide its settings menu and colapse it into one single menu (Settings and Vehicle Setup)? /// @return true if QGC should consolidate both menus into one. @@ -82,6 +83,7 @@ public: virtual bool guidedBarShowOrbit () const { return true; } virtual bool missionWaypointsOnly () const { return false; } ///< true: Only allow waypoints and complex items in Plan virtual bool multiVehicleEnabled () const { return true; } ///< false: multi vehicle support is disabled + virtual bool guidedActionsRequireRCRSSI () const { return false; } ///< true: Guided actions will be disabled is there is no RC RSSI #if defined(__mobile__) virtual bool showOfflineMapExport () const { return false; } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 457948e579289aeaade308589b500707e240ac29..9fa3240ba948b203d0e328f31a28a93134b9f5ed 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -67,7 +67,6 @@ enum DockWidgetTypes { MAVLINK_INSPECTOR, CUSTOM_COMMAND, ONBOARD_FILES, - DEPRECATED_WIDGET, HIL_CONFIG, ANALYZE }; @@ -76,7 +75,6 @@ static const char *rgDockWidgetNames[] = { "MAVLink Inspector", "Custom Command", "Onboard Files", - "Deprecated Widget", "HIL Config", "Analyze" };