Unverified Commit 858af395 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6279 from DonLakeFlyer/StableMerge

Stable merge
parents c4ff7197 47c6c032
......@@ -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()
}
}
......
......@@ -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
......
......@@ -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
......
......@@ -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();
}
......@@ -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<QGCFencePolygon>& polygons,
const QList<QGCFenceCircle>& 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<QGCFencePolygon>& polygons, const QList<QGCFenceCircle>& 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
......@@ -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;
};
......
......@@ -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;
......
......@@ -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)
}
}
......
......@@ -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
......@@ -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 }
}
}
......
......@@ -21,8 +21,6 @@
/// @brief Core Plugin Interface for QGroundControl
/// @author Gus Grubba <mavlink@grubba.com>
// 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
......
......@@ -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; }
......
......@@ -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"
};
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment