Unverified Commit f95fbf70 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7105 from DonLakeFlyer/GuidedCancel

Better handling of guided map indicator show/hide
parents 50a42e36 9ad555d0
...@@ -84,6 +84,7 @@ public: ...@@ -84,6 +84,7 @@ public:
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const override; QString flightMode (uint8_t base_mode, uint32_t custom_mode) const override;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) override; bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) override;
bool isGuidedMode (const Vehicle* vehicle) const override; bool isGuidedMode (const Vehicle* vehicle) const override;
QString gotoFlightMode (void) const override { return QStringLiteral("Guided"); }
QString rtlFlightMode (void) const override { return QString("RTL"); } QString rtlFlightMode (void) const override { return QString("RTL"); }
QString missionFlightMode (void) const override { return QString("Auto"); } QString missionFlightMode (void) const override { return QString("Auto"); }
void pauseVehicle (Vehicle* vehicle) override; void pauseVehicle (Vehicle* vehicle) override;
......
...@@ -757,3 +757,8 @@ int FirmwarePlugin::versionCompare(Vehicle* vehicle, QString& compare) ...@@ -757,3 +757,8 @@ int FirmwarePlugin::versionCompare(Vehicle* vehicle, QString& compare)
int patch = versionNumbers[2].toInt(); int patch = versionNumbers[2].toInt();
return versionCompare(vehicle, major, minor, patch); return versionCompare(vehicle, major, minor, patch);
} }
QString FirmwarePlugin::gotoFlightMode(void) const
{
return QString();
}
...@@ -114,6 +114,9 @@ public: ...@@ -114,6 +114,9 @@ public:
/// Returns whether the vehicle is in guided mode or not. /// Returns whether the vehicle is in guided mode or not.
virtual bool isGuidedMode(const Vehicle* vehicle) const; virtual bool isGuidedMode(const Vehicle* vehicle) const;
/// Returns the flight mode which the vehicle will be in if it is performing a goto location
virtual QString gotoFlightMode(void) const;
/// Set guided flight mode /// Set guided flight mode
virtual void setGuidedMode(Vehicle* vehicle, bool guidedMode); virtual void setGuidedMode(Vehicle* vehicle, bool guidedMode);
......
...@@ -42,6 +42,7 @@ public: ...@@ -42,6 +42,7 @@ public:
QString rtlFlightMode (void) const override { return _rtlFlightMode; } QString rtlFlightMode (void) const override { return _rtlFlightMode; }
QString landFlightMode (void) const override { return _landingFlightMode; } QString landFlightMode (void) const override { return _landingFlightMode; }
QString takeControlFlightMode (void) const override { return _manualFlightMode; } QString takeControlFlightMode (void) const override { return _manualFlightMode; }
QString gotoFlightMode (void) const override { return _holdFlightMode; }
void pauseVehicle (Vehicle* vehicle) override; void pauseVehicle (Vehicle* vehicle) override;
void guidedModeRTL (Vehicle* vehicle) override; void guidedModeRTL (Vehicle* vehicle) override;
void guidedModeLand (Vehicle* vehicle) override; void guidedModeLand (Vehicle* vehicle) override;
......
...@@ -295,6 +295,7 @@ FlightMap { ...@@ -295,6 +295,7 @@ FlightMap {
} }
} }
// GoTo Location visuals
MapQuickItem { MapQuickItem {
id: gotoLocationItem id: gotoLocationItem
visible: false visible: false
...@@ -308,6 +309,22 @@ FlightMap { ...@@ -308,6 +309,22 @@ FlightMap {
label: qsTr("Goto here", "Goto here waypoint") label: qsTr("Goto here", "Goto here waypoint")
} }
property bool inGotoFlightMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.gotoFlightMode : false
property var activeVehicle: _activeVehicle
onInGotoFlightModeChanged: {
if (!inGotoFlightMode && visible) {
// Hide goto indicator when vehicle falls out of guided mode
visible = false
}
}
onActiveVehicleChanged: {
if (!_activeVehicle) {
visible = false
}
}
function show(coord) { function show(coord) {
gotoLocationItem.coordinate = coord gotoLocationItem.coordinate = coord
gotoLocationItem.visible = true gotoLocationItem.visible = true
...@@ -316,10 +333,17 @@ FlightMap { ...@@ -316,10 +333,17 @@ FlightMap {
function hide() { function hide() {
gotoLocationItem.visible = false gotoLocationItem.visible = false
} }
}
// Orbit visuals function actionConfirmed() {
// We leave the indicator visible. The handling for onInGuidedModeChanged will hide it.
}
function actionCancelled() {
hide()
}
}
// Orbit editing visuals
QGCMapCircleVisuals { QGCMapCircleVisuals {
id: orbitMapCircle id: orbitMapCircle
mapControl: parent mapControl: parent
...@@ -328,9 +352,16 @@ FlightMap { ...@@ -328,9 +352,16 @@ FlightMap {
property alias center: _mapCircle.center property alias center: _mapCircle.center
property alias clockwiseRotation: _mapCircle.clockwiseRotation property alias clockwiseRotation: _mapCircle.clockwiseRotation
property var activeVehicle: _activeVehicle
readonly property real defaultRadius: 30 readonly property real defaultRadius: 30
onActiveVehicleChanged: {
if (!_activeVehicle) {
visible = false
}
}
function show(coord) { function show(coord) {
_mapCircle.radius.rawValue = defaultRadius _mapCircle.radius.rawValue = defaultRadius
orbitMapCircle.center = coord orbitMapCircle.center = coord
...@@ -341,6 +372,15 @@ FlightMap { ...@@ -341,6 +372,15 @@ FlightMap {
orbitMapCircle.visible = false orbitMapCircle.visible = false
} }
function actionConfirmed() {
// Live orbit status is handled by telemetry so we hide here and telemetry will show again.
hide()
}
function actionCancelled() {
hide()
}
function radius() { function radius() {
return _mapCircle.radius.rawValue return _mapCircle.radius.rawValue
} }
...@@ -357,7 +397,6 @@ FlightMap { ...@@ -357,7 +397,6 @@ FlightMap {
} }
// Orbit telemetry visuals // Orbit telemetry visuals
QGCMapCircleVisuals { QGCMapCircleVisuals {
id: orbitTelemetryCircle id: orbitTelemetryCircle
mapControl: parent mapControl: parent
...@@ -395,7 +434,7 @@ FlightMap { ...@@ -395,7 +434,7 @@ FlightMap {
onTriggered: { onTriggered: {
gotoLocationItem.show(clickMenu.coord) gotoLocationItem.show(clickMenu.coord)
orbitMapCircle.hide() orbitMapCircle.hide()
guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickMenu.coord) guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickMenu.coord, gotoLocationItem)
} }
} }
...@@ -406,7 +445,7 @@ FlightMap { ...@@ -406,7 +445,7 @@ FlightMap {
onTriggered: { onTriggered: {
orbitMapCircle.show(clickMenu.coord) orbitMapCircle.show(clickMenu.coord)
gotoLocationItem.hide() gotoLocationItem.hide()
guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickMenu.coord) guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickMenu.coord, orbitMapCircle)
} }
} }
} }
......
...@@ -34,16 +34,14 @@ Rectangle { ...@@ -34,16 +34,14 @@ Rectangle {
property int action property int action
property var actionData property var actionData
property bool hideTrigger: false property bool hideTrigger: false
property var mapIndicator
property real _margins: ScreenTools.defaultFontPixelWidth property real _margins: ScreenTools.defaultFontPixelWidth
property bool _emergencyAction: action === guidedController.actionEmergencyStop property bool _emergencyAction: action === guidedController.actionEmergencyStop
onHideTriggerChanged: { onHideTriggerChanged: {
if (hideTrigger) { if (hideTrigger) {
hideTrigger = false confirmCancelled()
altitudeSlider.visible = false
visibleTimer.stop()
visible = false
} }
} }
...@@ -57,6 +55,17 @@ Rectangle { ...@@ -57,6 +55,17 @@ Rectangle {
} }
} }
function confirmCancelled() {
altitudeSlider.visible = false
visible = false
hideTrigger = false
visibleTimer.stop()
if (mapIndicator) {
mapIndicator.actionCancelled()
mapIndicator = undefined
}
}
Timer { Timer {
id: visibleTimer id: visibleTimer
interval: 1000 interval: 1000
...@@ -107,12 +116,10 @@ Rectangle { ...@@ -107,12 +116,10 @@ Rectangle {
} }
hideTrigger = false hideTrigger = false
guidedController.executeAction(_root.action, _root.actionData, altitudeChange) guidedController.executeAction(_root.action, _root.actionData, altitudeChange)
} if (mapIndicator) {
mapIndicator.actionConfirmed()
onReject: { mapIndicator = undefined
altitudeSlider.visible = false }
_root.visible = false
hideTrigger = false
} }
} }
} }
...@@ -127,12 +134,10 @@ Rectangle { ...@@ -127,12 +134,10 @@ Rectangle {
source: "/res/XDelete.svg" source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit fillMode: Image.PreserveAspectFit
color: qgcPal.text color: qgcPal.text
QGCMouseArea { QGCMouseArea {
fillItem: parent fillItem: parent
onClicked: { onClicked: confirmCancelled()
altitudeSlider.visible = false
_root.visible = false
}
} }
} }
} }
...@@ -209,12 +209,13 @@ Item { ...@@ -209,12 +209,13 @@ Item {
} }
// Called when an action is about to be executed in order to confirm // Called when an action is about to be executed in order to confirm
function confirmAction(actionCode, actionData) { function confirmAction(actionCode, actionData, mapIndicator) {
var showImmediate = true var showImmediate = true
closeAll() closeAll()
confirmDialog.action = actionCode confirmDialog.action = actionCode
confirmDialog.actionData = actionData confirmDialog.actionData = actionData
confirmDialog.hideTrigger = true confirmDialog.hideTrigger = true
confirmDialog.mapIndicator = mapIndicator
_actionData = actionData _actionData = actionData
switch (actionCode) { switch (actionCode) {
case actionArm: case actionArm:
...@@ -385,7 +386,6 @@ Item { ...@@ -385,7 +386,6 @@ Item {
break break
case actionOrbit: case actionOrbit:
_activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius() * (orbitMapCircle.clockwiseRotation ? 1 : -1), _activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange) _activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius() * (orbitMapCircle.clockwiseRotation ? 1 : -1), _activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange)
orbitMapCircle.hide()
break break
case actionLandAbort: case actionLandAbort:
_activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored _activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored
......
...@@ -14,7 +14,6 @@ Rectangle { ...@@ -14,7 +14,6 @@ Rectangle {
color: qgcPal.windowShade color: qgcPal.windowShade
signal accept ///< Action confirmed signal accept ///< Action confirmed
signal reject ///< Action rejected
property string confirmText ///< Text for slider property string confirmText ///< Text for slider
property alias fontPointSize: label.font.pointSize ///< Point size for text property alias fontPointSize: label.font.pointSize ///< Point size for text
...@@ -70,12 +69,6 @@ Rectangle { ...@@ -70,12 +69,6 @@ Rectangle {
property bool dragActive: drag.active property bool dragActive: drag.active
property real _dragOffset: 1 property real _dragOffset: 1
//Component.onCompleted: console.log(height, ScreenTools.minTouchPixels)
onPressed: {
mouse.x
}
onDragActiveChanged: { onDragActiveChanged: {
if (!sliderDragArea.drag.active) { if (!sliderDragArea.drag.active) {
if (slider.x > _maxXDrag - _border) { if (slider.x > _maxXDrag - _border) {
......
...@@ -2962,6 +2962,11 @@ bool Vehicle::takeoffVehicleSupported() const ...@@ -2962,6 +2962,11 @@ bool Vehicle::takeoffVehicleSupported() const
return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability); return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
} }
QString Vehicle::gotoFlightMode() const
{
return _firmwarePlugin->gotoFlightMode();
}
void Vehicle::guidedModeRTL(void) void Vehicle::guidedModeRTL(void)
{ {
if (!guidedModeSupported()) { if (!guidedModeSupported()) {
......
...@@ -636,13 +636,14 @@ public: ...@@ -636,13 +636,14 @@ public:
Q_PROPERTY(QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT) Q_PROPERTY(QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT)
// Vehicle state used for guided control // Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) ///< Vehicle is in landing pattern (DO_LAND_START) Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) ///< Vehicle is in landing pattern (DO_LAND_START)
Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) ///< Vehicle is in Guided mode and can respond to guided commands Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) ///< Vehicle is in Guided mode and can respond to guided commands
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT) ///< Flight mode vehicle is in while performing goto
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT) Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
...@@ -761,10 +762,11 @@ public: ...@@ -761,10 +762,11 @@ public:
/// @param percent 0-no power, 100-full power /// @param percent 0-no power, 100-full power
Q_INVOKABLE void motorTest(int motor, int percent); Q_INVOKABLE void motorTest(int motor, int percent);
bool guidedModeSupported (void) const; bool guidedModeSupported (void) const;
bool pauseVehicleSupported (void) const; bool pauseVehicleSupported (void) const;
bool orbitModeSupported (void) const; bool orbitModeSupported (void) const;
bool takeoffVehicleSupported(void) const; bool takeoffVehicleSupported (void) const;
QString gotoFlightMode (void) const;
// Property accessors // Property accessors
......
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