Browse Source

Major cleanup to Guided Bar

QGC4.4
DonLakeFlyer 8 years ago
parent
commit
774fad4ef6
  1. 10
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 2
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  3. 24
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  4. 9
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
  5. 5
      src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
  6. 1
      src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
  7. 22
      src/FirmwarePlugin/FirmwarePlugin.cc
  8. 35
      src/FirmwarePlugin/FirmwarePlugin.h
  9. 30
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  10. 8
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  11. 280
      src/FlightDisplay/FlightDisplayViewWidgets.qml
  12. 1
      src/FlightMap/FlightMap.qml
  13. 1
      src/FlightMap/qmldir
  14. 16
      src/MissionManager/SimpleMissionItem.cc
  15. 50
      src/QmlControls/QGCSlider.qml
  16. 1
      src/QmlControls/ScreenTools.qml
  17. 6
      src/QmlControls/SliderSwitch.qml
  18. 14
      src/Vehicle/Vehicle.cc
  19. 9
      src/Vehicle/Vehicle.h

10
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -806,13 +806,3 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return QString(); return QString();
} }
} }
QString APMFirmwarePlugin::missionFlightMode(void)
{
return QStringLiteral("Auto");
}
QString APMFirmwarePlugin::rtlFlightMode(void)
{
return QStringLiteral("RTL");
}

2
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -97,8 +97,6 @@ public:
RallyPointManager* newRallyPointManager (Vehicle* vehicle) { return new APMRallyPointManager(vehicle); } RallyPointManager* newRallyPointManager (Vehicle* vehicle) { return new APMRallyPointManager(vehicle); }
QString brandImageIndoor (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } QString brandImageIndoor (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
QString brandImageOutdoor (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
QString missionFlightMode (void) final;
QString rtlFlightMode (void) final;
protected: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation

24
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -162,13 +162,22 @@ void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QG
vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */); vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */);
} }
void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{ {
if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
qgcApp()->showMessage(QStringLiteral("Unable to change altitude, vehicle altitude not known.")); qgcApp()->showMessage(QStringLiteral("Unable to change altitude, vehicle altitude not known."));
return; return;
} }
// Don't allow altitude to fall below 3 meters above home
double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
if (altitudeChange <= 0 && currentAltRel <= 3) {
return;
}
if (currentAltRel + altitudeChange < 3) {
altitudeChange = 3 - currentAltRel;
}
mavlink_message_t msg; mavlink_message_t msg;
mavlink_set_position_target_local_ned_t cmd; mavlink_set_position_target_local_ned_t cmd;
@ -180,7 +189,7 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
cmd.type_mask = 0xFFF8; // Only x/y/z valid cmd.type_mask = 0xFFF8; // Only x/y/z valid
cmd.x = 0.0f; cmd.x = 0.0f;
cmd.y = 0.0f; cmd.y = 0.0f;
cmd.z = -(altitudeRel - vehicle->altitudeRelative()->rawValue().toDouble()); cmd.z = -(altitudeChange);
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_msg_set_position_target_local_ned_encode_chan(mavlink->getSystemId(), mavlink_msg_set_position_target_local_ned_encode_chan(mavlink->getSystemId(),
@ -192,11 +201,6 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
vehicle->sendMessageOnLink(vehicle->priorityLink(), msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
bool ArduCopterFirmwarePlugin::isPaused(const Vehicle* vehicle) const
{
return vehicle->flightMode() == "Brake";
}
void ArduCopterFirmwarePlugin::pauseVehicle(Vehicle* vehicle) void ArduCopterFirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{ {
vehicle->setFlightMode("Brake"); vehicle->setFlightMode("Brake");
@ -228,12 +232,6 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
return QStringLiteral("FENCE_RADIUS"); return QStringLiteral("FENCE_RADIUS");
} }
QString ArduCopterFirmwarePlugin::takeControlFlightMode(void)
{
return QStringLiteral("Stabilize");
}
bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{ {
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"))) { if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"))) {

9
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h

@ -54,7 +54,6 @@ public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) final; bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) final;
bool isPaused(const Vehicle* vehicle) const final;
void setGuidedMode(Vehicle* vehicle, bool guidedMode) final; void setGuidedMode(Vehicle* vehicle, bool guidedMode) final;
void pauseVehicle(Vehicle* vehicle) final; void pauseVehicle(Vehicle* vehicle) final;
void guidedModeRTL(Vehicle* vehicle) final; void guidedModeRTL(Vehicle* vehicle) final;
@ -64,14 +63,18 @@ public:
void guidedModeTakeoff(Vehicle* vehicle) final; void guidedModeTakeoff(Vehicle* vehicle) final;
#endif #endif
void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final; void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final;
void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) final; void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) final;
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; } const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final; int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
bool multiRotorCoaxialMotors(Vehicle* vehicle) final; bool multiRotorCoaxialMotors(Vehicle* vehicle) final;
bool multiRotorXConfig(Vehicle* vehicle) final; bool multiRotorXConfig(Vehicle* vehicle) final;
QString geoFenceRadiusParam(Vehicle* vehicle) final; QString geoFenceRadiusParam(Vehicle* vehicle) final;
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); } QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); }
QString takeControlFlightMode(void) final; QString pauseFlightMode(void) const override { return QString("Brake"); }
QString missionFlightMode(void) const override { return QString("Auto"); }
QString rtlFlightMode(void) const override { return QString("RTL"); }
QString landFlightMode(void) const override { return QString("Land"); }
QString takeControlFlightMode(void) const override { return QString("Stablize"); }
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const final; bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const final;
private: private:

5
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc

@ -86,8 +86,3 @@ int ArduPlaneFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVer
// Remapping supports up to 3.8 // Remapping supports up to 3.8
return majorVersionNumber == 3 ? 8 : Vehicle::versionNotSetValue; return majorVersionNumber == 3 ? 8 : Vehicle::versionNotSetValue;
} }
QString ArduPlaneFirmwarePlugin::takeControlFlightMode(void)
{
return QStringLiteral("Manual");
}

1
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h

@ -57,7 +57,6 @@ public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); } QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); }
QString takeControlFlightMode(void) final;
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; } const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final; int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;

22
src/FirmwarePlugin/FirmwarePlugin.cc

@ -237,13 +237,6 @@ void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
bool FirmwarePlugin::isPaused(const Vehicle* vehicle) const
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
return false;
}
void FirmwarePlugin::pauseVehicle(Vehicle* vehicle) void FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
@ -314,21 +307,6 @@ int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumbe
return 0; return 0;
} }
QString FirmwarePlugin::missionFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::rtlFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::takeControlFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::vehicleImageOpaque(const Vehicle* vehicle) const QString FirmwarePlugin::vehicleImageOpaque(const Vehicle* vehicle) const
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);

35
src/FirmwarePlugin/FirmwarePlugin.h

@ -93,15 +93,27 @@ public:
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message /// @param[out] custom_mode Custom mode for SET_MODE mavlink message
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
/// Returns The flight mode which indicates the vehicle is paused
virtual QString pauseFlightMode(void) const { return QString(); }
/// Returns the flight mode for running missions
virtual QString missionFlightMode(void) const { return QString(); }
/// Returns the flight mode for RTL
virtual QString rtlFlightMode(void) const { return QString(); }
/// Returns the flight mode for Land
virtual QString landFlightMode(void) const { return QString(); }
/// Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual QString takeControlFlightMode(void) const { return QString(); }
/// 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;
/// Set guided flight mode /// Set guided flight mode
virtual void setGuidedMode(Vehicle* vehicle, bool guidedMode); virtual void setGuidedMode(Vehicle* vehicle, bool guidedMode);
/// Returns whether the vehicle is paused or not.
virtual bool isPaused(const Vehicle* vehicle) const;
/// Causes the vehicle to stop at current position. If guide mode is supported, vehicle will be let in guide mode. /// Causes the vehicle to stop at current position. If guide mode is supported, vehicle will be let in guide mode.
/// If not, vehicle will be left in Loiter. /// If not, vehicle will be left in Loiter.
virtual void pauseVehicle(Vehicle* vehicle); virtual void pauseVehicle(Vehicle* vehicle);
@ -125,20 +137,9 @@ public:
/// Command vehicle to move to specified location (altitude is included and relative) /// Command vehicle to move to specified location (altitude is included and relative)
virtual void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord); virtual void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord);
/// Command vehicle to change to the specified relatice altitude /// Command vehicle to change altitude
virtual void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel); /// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
virtual void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange);
/// Returns the flight mode for running missions
virtual QString missionFlightMode(void);
/// Returns the flight mode for RTL
virtual QString rtlFlightMode(void);
/// Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual QString takeControlFlightMode(void);
/// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific /// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific
/// not just this. I'm going to try to change that. If not, this will need to be removed. /// not just this. I'm going to try to change that. If not, this will need to be removed.

30
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -399,7 +399,7 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
vehicle->altitudeAMSL()->rawValue().toFloat()); vehicle->altitudeAMSL()->rawValue().toFloat());
} }
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{ {
if (!vehicle->homePositionAvailable()) { if (!vehicle->homePositionAvailable()) {
qgcApp()->showMessage(tr("Unable to change altitude, home position unknown.")); qgcApp()->showMessage(tr("Unable to change altitude, home position unknown."));
@ -410,6 +410,17 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
return; return;
} }
// Don't allow altitude to fall below 3 meters above home
double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
double newAltRel = currentAltRel;
if (altitudeChange <= 0 && currentAltRel <= 3) {
return;
}
if (currentAltRel + altitudeChange < 3) {
altitudeChange = 3 - currentAltRel;
}
newAltRel = currentAltRel + altitudeChange;
vehicle->sendMavCommand(vehicle->defaultComponentId(), vehicle->sendMavCommand(vehicle->defaultComponentId(),
MAV_CMD_DO_REPOSITION, MAV_CMD_DO_REPOSITION,
true, // show error is fails true, // show error is fails
@ -419,7 +430,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
NAN, NAN,
NAN, NAN,
NAN, NAN,
vehicle->homePosition().altitude() + altitudeRel); vehicle->homePosition().altitude() + newAltRel);
} }
void PX4FirmwarePlugin::startMission(Vehicle* vehicle) void PX4FirmwarePlugin::startMission(Vehicle* vehicle)
@ -504,21 +515,6 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
} }
} }
QString PX4FirmwarePlugin::missionFlightMode(void)
{
return QString(_missionFlightMode);
}
QString PX4FirmwarePlugin::rtlFlightMode(void)
{
return QString(_rtlFlightMode);
}
QString PX4FirmwarePlugin::takeControlFlightMode(void)
{
return QString(_manualFlightMode);
}
bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{ {
if ( vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"))) { if ( vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"))) {

8
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -37,6 +37,11 @@ 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;
void setGuidedMode (Vehicle* vehicle, bool guidedMode) override; void setGuidedMode (Vehicle* vehicle, bool guidedMode) override;
QString pauseFlightMode (void) const override { return _holdFlightMode; }
QString missionFlightMode (void) const override { return _missionFlightMode; }
QString rtlFlightMode (void) const override { return _rtlFlightMode; }
QString landFlightMode (void) const override { return _landingFlightMode; }
QString takeControlFlightMode (void) const override { return _manualFlightMode; }
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;
@ -61,9 +66,6 @@ public:
QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); } QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
QString missionFlightMode (void) override;
QString rtlFlightMode (void) override;
QString takeControlFlightMode (void) override;
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override; bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override;
protected: protected:

280
src/FlightDisplay/FlightDisplayViewWidgets.qml

@ -7,13 +7,13 @@
* *
****************************************************************************/ ****************************************************************************/
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4 import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QtLocation 5.3 import QtLocation 5.3
import QtPositioning 5.3 import QtPositioning 5.3
import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
@ -38,6 +38,9 @@ Item {
// Guided bar properties // Guided bar properties
property bool _missionAvailable: missionController.containsItems property bool _missionAvailable: missionController.containsItems
property bool _missionActive: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.missionFlightMode : false property bool _missionActive: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.missionFlightMode : false
property bool _vehiclePaused: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.pauseFlightMode : false
property bool _vehicleInRTLMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.rtlFlightMode : false
property bool _vehicleInLandMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.landFlightMode : false
property int _resumeMissionItem: missionController.resumeMissionItem property int _resumeMissionItem: missionController.resumeMissionItem
property bool _showEmergenyStop: QGroundControl.corePlugin.options.guidedBarShowEmergencyStop property bool _showEmergenyStop: QGroundControl.corePlugin.options.guidedBarShowEmergencyStop
property bool _showOrbit: QGroundControl.corePlugin.options.guidedBarShowOrbit property bool _showOrbit: QGroundControl.corePlugin.options.guidedBarShowOrbit
@ -171,58 +174,30 @@ Item {
anchors.margins: _barMargin anchors.margins: _barMargin
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
width: guidedModeColumn.width + (_margins * 2) width: (guidedModeButtons.visible ? guidedModeButtons.width : guidedModeConfirm.width) + (_margins * 2)
height: guidedModeColumn.height + (_margins * 2) height: (guidedModeButtons.visible ? guidedModeButtons.height : guidedModeConfirm.height) + (_margins * 2)
radius: ScreenTools.defaultFontPixelHeight * 0.25 radius: ScreenTools.defaultFontPixelHeight * 0.25
color: _isSatellite ? Qt.rgba(qgcPal.mapWidgetBorderLight.r, qgcPal.mapWidgetBorderLight.g, qgcPal.mapWidgetBorderLight.b, 0.8) : Qt.rgba(qgcPal.mapWidgetBorderDark.r, qgcPal.mapWidgetBorderDark.g, qgcPal.mapWidgetBorderDark.b, 0.75) color: _backgroundColor
visible: _activeVehicle visible: _activeVehicle
z: QGroundControl.zOrderWidgets z: QGroundControl.zOrderWidgets
state: "Shown"
property real _fontPointSize: ScreenTools.isMobile ? ScreenTools.largeFontPointSize : ScreenTools.defaultFontPointSize property real _fontPointSize: ScreenTools.isMobile ? ScreenTools.largeFontPointSize : ScreenTools.defaultFontPointSize
property color _backgroundColor: _isSatellite ? qgcPal.mapWidgetBorderLight : qgcPal.mapWidgetBorderDark
property color _textColor: _isSatellite ? qgcPal.mapWidgetBorderDark : qgcPal.mapWidgetBorderLight
property string _emergencyStopTitle: qsTr("Emergency Stop")
property string _armTitle: qsTr("Arm")
property string _disarmTitle: qsTr("Disarm")
property string _rtlTitle: qsTr("RTL")
property string _takeoffTitle: qsTr("Takeoff")
property string _landTitle: qsTr("Land")
property string _startMissionTitle: qsTr("Start Mission")
property string _resumeMissionTitle: qsTr("Resume Mission")
property string _pauseTitle: _missionActive ? qsTr("Pause Mission") : qsTr("Pause")
property string _changeAltTitle: qsTr("Change Altitude")
property string _orbitTitle: qsTr("Orbit")
property string _abortTitle: qsTr("Abort")
states: [
State {
name: "Shown"
PropertyChanges { target: showAnimation; running: true }
PropertyChanges { target: guidedModeHideTimer; running: true }
},
State {
name: "Hidden"
PropertyChanges { target: hideAnimation; running: true }
}
]
PropertyAnimation {
id: hideAnimation
target: _guidedModeBar
property: "_barMargin"
duration: 1000
easing.type: Easing.InOutQuad
from: _guidedModeBar._showMargin
to: _guidedModeBar._hideMargin
}
PropertyAnimation {
id: showAnimation
target: _guidedModeBar
property: "_barMargin"
duration: 250
easing.type: Easing.InOutQuad
from: _guidedModeBar._hideMargin
to: _guidedModeBar._showMargin
}
Timer {
id: guidedModeHideTimer
interval: 7000
running: true
onTriggered: {
if (ScreenTools.isTinyScreen) {
_guidedModeBar.state = "Hidden"
}
}
}
readonly property int confirmHome: 1 readonly property int confirmHome: 1
readonly property int confirmLand: 2 readonly property int confirmLand: 2
@ -274,10 +249,7 @@ Item {
_activeVehicle.emergencyStop() _activeVehicle.emergencyStop()
break; break;
case confirmChangeAlt: case confirmChangeAlt:
var altitude2 = altitudeSlider.getValue() _activeVehicle.guidedModeChangeAltitude(altitudeSlider.getValue())
if (!isNaN(altitude2)) {
_activeVehicle.guidedModeChangeAltitude(altitude2)
}
break; break;
case confirmGoTo: case confirmGoTo:
_activeVehicle.guidedModeGotoLocation(_flightMap._gotoHereCoordinate) _activeVehicle.guidedModeGotoLocation(_flightMap._gotoHereCoordinate)
@ -300,68 +272,80 @@ Item {
} }
function rejectGuidedModeConfirm() { function rejectGuidedModeConfirm() {
guidedModeButtons.visible = true
guidedModeConfirm.visible = false guidedModeConfirm.visible = false
_guidedModeBar.visible = true
altitudeSlider.visible = false altitudeSlider.visible = false
_flightMap._gotoHereCoordinate = QtPositioning.coordinate() _flightMap._gotoHereCoordinate = QtPositioning.coordinate()
guidedModeHideTimer.restart()
} }
function confirmAction(actionCode) { function confirmAction(actionCode) {
guidedModeHideTimer.stop()
confirmActionCode = actionCode confirmActionCode = actionCode
switch (confirmActionCode) { switch (confirmActionCode) {
case confirmArm: case confirmArm:
guidedModeConfirm.confirmText = qsTr("arm") guidedModeConfirm.title = _armTitle
guidedModeConfirm.message = qsTr("arm")
break; break;
case confirmDisarm: case confirmDisarm:
guidedModeConfirm.confirmText = qsTr("disarm") guidedModeConfirm.title = _disarmTitle
guidedModeConfirm.message = qsTr("disarm")
break; break;
case confirmEmergencyStop: case confirmEmergencyStop:
guidedModeConfirm.confirmText = qsTr("STOP ALL MOTORS!") guidedModeConfirm.title = _emergencyStopTitle
guidedModeConfirm.message = qsTr("WARNING: This still stop all motors. If vehicle is currently in air it will crash.")
break; break;
case confirmTakeoff: case confirmTakeoff:
guidedModeConfirm.confirmText = qsTr("takeoff") guidedModeConfirm.title = _takeoffTitle
guidedModeConfirm.message = qsTr("Takeoff from ground and hold position.")
break; break;
case confirmStartMission: case confirmStartMission:
guidedModeConfirm.confirmText = qsTr("start mission") guidedModeConfirm.title = _startMissionTitle
guidedModeConfirm.message = qsTr("Start the mission which is currently displayed above. If the vehicle is on the ground it will takeoff.")
break; break;
case confirmResumeMission: case confirmResumeMission:
guidedModeConfirm.confirmText = qsTr("resume mission") guidedModeConfirm.title = _resumeMissionTitle
guidedModeConfirm.message = qsTr("Resume the mission which is displayed above. This will re-generate the mission from waypoint %1, takeoff and continue the mission.").arg(_resumeMissionItem)
break; break;
case confirmResumeMissionReady: case confirmResumeMissionReady:
guidedModeConfirm.confirmText = qsTr("resume modified mission after review") guidedModeConfirm.title = _resumeMissionTitle
guidedModeConfirm.message = qsTr("Review the modified mission above. Confirm if you want to takeoff and begin mission.")
break; break;
case confirmLand: case confirmLand:
guidedModeConfirm.confirmText = qsTr("land") guidedModeConfirm.title = _landTitle
guidedModeConfirm.message = qsTr("Land the vehicle at the current position.")
break; break;
case confirmHome: case confirmHome:
guidedModeConfirm.confirmText = qsTr("return to land") guidedModeConfirm.title = _rtlTitle
guidedModeConfirm.message = qsTr("Return to the home position of the vehicle.")
break; break;
case confirmChangeAlt: case confirmChangeAlt:
altitudeSlider.visible = true altitudeSlider.visible = true
altitudeSlider.setInitialValueAppSettingsDistanceUnits(_activeVehicle.altitudeRelative.value) altitudeSlider.setValue(0)
guidedModeConfirm.confirmText = qsTr("change altitude") guidedModeConfirm.title = _changeAltTitle
guidedModeConfirm.message = qsTr("Adjust the slider to the left up or down to change the altitude of the vehicle.")
break; break;
case confirmGoTo: case confirmGoTo:
guidedModeConfirm.confirmText = qsTr("move vehicle") guidedModeConfirm.title = qsTr("Go To Location")
guidedModeConfirm.message = qsTr("Confirm to move to the new location.")
break; break;
case confirmRetask: case confirmRetask:
guidedModeConfirm.confirmText = qsTr("activate waypoint change") guidedModeConfirm.title = qsTr("Waypoint Change")
guidedModeConfirm.message = qsTr("Confirm to change current mission item to %1.").arg(_flightMap._retaskSequence)
break; break;
case confirmOrbit: case confirmOrbit:
guidedModeConfirm.confirmText = qsTr("enter orbit mode") guidedModeConfirm.title = _orbitTitle
guidedModeConfirm.message = qsTr("Confirm to enter Orbit mode.")
break; break;
case confirmAbort: case confirmAbort:
guidedModeConfirm.confirmText = qsTr("abort landing") guidedModeConfirm.title = _abortTitle
guidedModeConfirm.message = qsTr("Confirm to abort the current landing.")
break; break;
} }
_guidedModeBar.visible = false guidedModeButtons.visible = false
guidedModeConfirm.visible = true guidedModeConfirm.visible = true
} }
Column { ColumnLayout {
id: guidedModeColumn id: guidedModeButtons
anchors.margins: _margins anchors.margins: _margins
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
@ -369,8 +353,8 @@ Item {
QGCLabel { QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
color: _isSatellite ? qgcPal.mapWidgetBorderDark : qgcPal.mapWidgetBorderLight color: _guidedModeBar._textColor
text: "Click in map to move vehicle" text: qsTr("Click in map to move vehicle")
visible: gotoEnabled visible: gotoEnabled
} }
@ -379,111 +363,148 @@ Item {
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Emergency Stop") text: _guidedModeBar._emergencyStopTitle
visible: _showEmergenyStop && _activeVehicle && _activeVehicle.armed && _activeVehicle.flying visible: _showEmergenyStop && _activeVehicle && _activeVehicle.armed && _activeVehicle.flying
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmEmergencyStop) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmEmergencyStop)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Disarm") text: _guidedModeBar._disarmTitle
visible: _activeVehicle && _activeVehicle.armed && !_activeVehicle.flying visible: _activeVehicle && _activeVehicle.armed && !_activeVehicle.flying
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmDisarm) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmDisarm)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("RTL") text: _guidedModeBar._rtlTitle
visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.guidedModeSupported && _activeVehicle.flying visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.guidedModeSupported && _activeVehicle.flying && !_vehicleInRTLMode
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmHome) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmHome)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Takeoff") text: _guidedModeBar._takeoffTitle
visible: _activeVehicle && _activeVehicle.guidedModeSupported && !_activeVehicle.flying && !_activeVehicle.fixedWing visible: _activeVehicle && _activeVehicle.guidedModeSupported && !_activeVehicle.flying && !_activeVehicle.fixedWing
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmTakeoff) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmTakeoff)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Land") text: _guidedModeBar._landTitle
visible: _activeVehicle && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_activeVehicle.fixedWing visible: _activeVehicle && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_activeVehicle.fixedWing && !_vehicleInLandMode
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmLand) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmLand)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: _resumeMissionItem !== -1 ? qsTr("Restart Mission") : qsTr("Start Mission") text: _guidedModeBar._startMissionTitle
visible: _activeVehicle && !_activeVehicle.flying && _missionAvailable visible: _activeVehicle && _missionAvailable && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmStartMission) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmStartMission)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Resume Mission (%1)").arg(_resumeMissionItem) text: _guidedModeBar._resumeMissionTitle
visible: _activeVehicle && !_activeVehicle.flying && _missionAvailable && _resumeMissionItem !== -1 visible: _activeVehicle && !_activeVehicle.flying && _missionAvailable && _resumeMissionItem !== -1
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmResumeMission) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmResumeMission)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: _missionActive ? qsTr("Pause Mission") : qsTr("Pause") text: _guidedModeBar._pauseTitle
visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.pauseVehicleSupported && _activeVehicle.flying visible: _activeVehicle && _activeVehicle.armed && _activeVehicle.pauseVehicleSupported && _activeVehicle.flying && !_vehiclePaused
onClicked: _activeVehicle.pauseVehicle() onClicked: _activeVehicle.pauseVehicle()
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Change Altitude") text: _guidedModeBar._changeAltTitle
visible: (_activeVehicle && _activeVehicle.flying) && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_missionActive visible: (_activeVehicle && _activeVehicle.flying) && _activeVehicle.guidedModeSupported && _activeVehicle.armed && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmChangeAlt) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmChangeAlt)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Orbit") text: _guidedModeBar._orbitTitle
visible: _showOrbit && _activeVehicle && _activeVehicle.flying && _activeVehicle.orbitModeSupported && _activeVehicle.armed && !_missionActive visible: _showOrbit && _activeVehicle && _activeVehicle.flying && _activeVehicle.orbitModeSupported && _activeVehicle.armed && !_missionActive
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmOrbit) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmOrbit)
} }
QGCButton { QGCButton {
pointSize: _guidedModeBar._fontPointSize pointSize: _guidedModeBar._fontPointSize
text: qsTr("Abort") text: _guidedModeBar._abortTitle
visible: _activeVehicle && _activeVehicle.flying && _activeVehicle.fixedWing visible: _activeVehicle && _activeVehicle.flying && _activeVehicle.fixedWing
onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmAbort) onClicked: _guidedModeBar.confirmAction(_guidedModeBar.confirmAbort)
} }
}
}
} // Row Column {
} // Column id: guidedModeConfirm
} // Rectangle - Guided mode buttons anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
visible: false
MouseArea { property alias title: titleText.text
anchors.fill: parent property alias message: messageText.text
enabled: guidedModeConfirm.visible
onClicked: _guidedModeBar.rejectGuidedModeConfirm() QGCLabel {
id: titleText
anchors.left: slider.left
anchors.right: slider.right
color: _guidedModeBar._textColor
horizontalAlignment: Text.AlignHCenter
}
QGCLabel {
id: messageText
anchors.left: slider.left
anchors.right: slider.right
color: _guidedModeBar._textColor
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
} }
// Action confirmation control // Action confirmation control
SliderSwitch { SliderSwitch {
id: guidedModeConfirm id: slider
anchors.bottomMargin: _margins
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
visible: false
z: QGroundControl.zOrderWidgets
fontPointSize: _guidedModeBar._fontPointSize fontPointSize: _guidedModeBar._fontPointSize
confirmText: qsTr("Slide to confirm")
width: Math.max(implicitWidth, ScreenTools.defaultFontPixelWidth * 30)
onAccept: { onAccept: {
guidedModeButtons.visible = true
guidedModeConfirm.visible = false guidedModeConfirm.visible = false
_guidedModeBar.visible = true
_guidedModeBar.actionConfirmed()
altitudeSlider.visible = false altitudeSlider.visible = false
guidedModeHideTimer.restart() _guidedModeBar.actionConfirmed()
} }
onReject: _guidedModeBar.rejectGuidedModeConfirm() onReject: _guidedModeBar.rejectGuidedModeConfirm()
} }
}
QGCColoredImage {
anchors.margins: _margins
anchors.top: _guidedModeBar.top
anchors.right: _guidedModeBar.right
width: ScreenTools.defaultFontPixelHeight
height: width
sourceSize.height: width
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.alertText
visible: guidedModeConfirm.visible
QGCMouseArea {
fillItem: parent
onClicked: _guidedModeBar.rejectGuidedModeConfirm()
}
}
} // Rectangle - Guided mode buttons
//-- Altitude slider //-- Altitude slider
Rectangle { Rectangle {
@ -492,27 +513,17 @@ Item {
anchors.right: parent.right anchors.right: parent.right
anchors.top: parent.top anchors.top: parent.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
color: qgcPal.window radius: ScreenTools.defaultFontPixelWidth / 2
width: ScreenTools.defaultFontPixelWidth * 10 width: ScreenTools.defaultFontPixelWidth * 10
opacity: 0.8 color: qgcPal.window
visible: false visible: false
function setInitialValueMeters(meters) { function setValue(value) {
altSlider.value = QGroundControl.metersToAppSettingsDistanceUnits(meters) altSlider.value = value
} }
function setInitialValueAppSettingsDistanceUnits(height) {
altSlider.value = height
}
/// Returns NaN for bad value
function getValue() { function getValue() {
var value = parseFloat(altField.text) return altSlider.value
if (!isNaN(value)) {
return QGroundControl.appSettingsDistanceUnitsToMeters(value);
} else {
return value;
}
} }
Column { Column {
@ -524,23 +535,17 @@ Item {
QGCLabel { QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
text: qsTr("Alt (rel)") text: altSlider.value >=0 ? qsTr("Up") : qsTr("Down")
} }
QGCLabel { QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: QGroundControl.appSettingsDistanceUnitsString
}
QGCTextField {
id: altField id: altField
anchors.left: parent.left anchors.horizontalCenter: parent.horizontalCenter
anchors.right: parent.right text: Math.abs(altSlider.value.toFixed(1)) + " " + QGroundControl.appSettingsDistanceUnitsString
text: altSlider.value.toFixed(1)
} }
} }
Slider { QGCSlider {
id: altSlider id: altSlider
anchors.margins: _margins anchors.margins: _margins
anchors.top: headerColumn.bottom anchors.top: headerColumn.bottom
@ -548,8 +553,19 @@ Item {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
orientation: Qt.Vertical orientation: Qt.Vertical
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(0) //minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(0)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits((_activeVehicle && _activeVehicle.flying) ? Math.round((_activeVehicle.altitudeRelative.value + 100) / 100) * 100 : 10) //maximumValue: QGroundControl.metersToAppSettingsDistanceUnits((_activeVehicle && _activeVehicle.flying) ? Math.round((_activeVehicle.altitudeRelative.value + 100) / 100) * 100 : 10)
minimumValue: QGroundControl.metersToAppSettingsDistanceUnits(-10)
maximumValue: QGroundControl.metersToAppSettingsDistanceUnits(10)
indicatorCentered: true
rotation: 180
// We want slide up to be positive values
transform: Rotation {
origin.x: altSlider.width / 2
origin.y: altSlider.height / 2
angle: 180
}
} }
} }
} }

1
src/FlightMap/FlightMap.qml

@ -54,6 +54,7 @@ Map {
function _possiblyCenterToVehiclePosition() { function _possiblyCenterToVehiclePosition() {
if (!firstVehiclePositionReceived && allowVehicleLocationCenter && activeVehicleCoordinate.isValid) { if (!firstVehiclePositionReceived && allowVehicleLocationCenter && activeVehicleCoordinate.isValid) {
console.log("Moving to initial vehicle position", QGroundControl.flightMapInitialZoom)
firstVehiclePositionReceived = true firstVehiclePositionReceived = true
center = activeVehicleCoordinate center = activeVehicleCoordinate
zoomLevel = QGroundControl.flightMapInitialZoom zoomLevel = QGroundControl.flightMapInitialZoom

1
src/FlightMap/qmldir

@ -17,7 +17,6 @@ QGCAttitudeHUD 1.0 QGCAttitudeHUD.qml
QGCAttitudeWidget 1.0 QGCAttitudeWidget.qml QGCAttitudeWidget 1.0 QGCAttitudeWidget.qml
QGCCompassWidget 1.0 QGCCompassWidget.qml QGCCompassWidget 1.0 QGCCompassWidget.qml
QGCPitchIndicator 1.0 QGCPitchIndicator.qml QGCPitchIndicator 1.0 QGCPitchIndicator.qml
QGCSlider 1.0 QGCSlider.qml
ValuesWidget 1.0 ValuesWidget.qml ValuesWidget 1.0 ValuesWidget.qml
VehicleHealthWidget 1.0 VehicleHealthWidget.qml VehicleHealthWidget 1.0 VehicleHealthWidget.qml
VibrationWidget 1.0 VibrationWidget.qml VibrationWidget 1.0 VibrationWidget.qml

16
src/MissionManager/SimpleMissionItem.cc

@ -498,7 +498,21 @@ bool SimpleMissionItem::friendlyEditAllowed(void) const
} }
if (specifiesCoordinate() || specifiesAltitudeOnly()) { if (specifiesCoordinate() || specifiesAltitudeOnly()) {
return _missionItem.frame() == MAV_FRAME_GLOBAL || _missionItem.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT; MAV_FRAME frame = _missionItem.frame();
switch (frame) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
#if 0
Coming soon
case MAV_FRAME_GLOBAL_INT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
#endif
return true;
break;
default:
return false;
}
} }
return true; return true;

50
src/QmlControls/QGCSlider.qml

@ -10,47 +10,63 @@
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4 import QtQuick.Controls.Styles 1.4
import QtQuick.Controls.Private 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QtQuick.Controls.Private 1.0
Slider { Slider {
property var _qgcPal: QGCPalette { colorGroupEnabled: enabled } id: _root
implicitHeight: ScreenTools.implicitSliderHeight
// Value indicator starts display from center instead of min value
property bool indicatorCentered: false
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
style: SliderStyle { style: SliderStyle {
groove: Item { groove: Item {
property color fillColor: "#49d"
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
implicitWidth: Math.round(TextSingleton.implicitHeight * 4.5) implicitWidth: Math.round(ScreenTools.defaultFontPixelHeight * 4.5)
implicitHeight: Math.max(6, Math.round(TextSingleton.implicitHeight * 0.3)) implicitHeight: Math.round(ScreenTools.defaultFontPixelHeight * 0.3)
Rectangle { Rectangle {
radius: height/2 radius: height / 2
anchors.fill: parent anchors.fill: parent
color: qgcPal.button
border.width: 1 border.width: 1
border.color: "#888" border.color: qgcPal.buttonText
gradient: Gradient {
GradientStop { color: "#bbb" ; position: 0 }
GradientStop { color: "#ccc" ; position: 0.6 }
GradientStop { color: "#ccc" ; position: 1 }
}
} }
Item { Item {
clip: true clip: true
width: styleData.handlePosition x: _root.indicatorCentered ? indicatorCenteredIndicatorStart : 0
width: _root.indicatorCentered ? centerIndicatorWidth : styleData.handlePosition
height: parent.height height: parent.height
property real indicatorCenteredIndicatorStart: Math.min(styleData.handlePosition, parent.width / 2)
property real indicatorCenteredIndicatorStop: Math.max(styleData.handlePosition, parent.width / 2)
property real centerIndicatorWidth: indicatorCenteredIndicatorStop - indicatorCenteredIndicatorStart
Rectangle { Rectangle {
anchors.fill: parent anchors.fill: parent
border.color: Qt.darker(fillColor, 1.2) color: qgcPal.colorBlue
border.color: Qt.darker(color, 1.2)
radius: height/2 radius: height/2
gradient: Gradient {
GradientStop {color: Qt.lighter(fillColor, 1.3) ; position: 0}
GradientStop {color: fillColor ; position: 1.4}
} }
} }
} }
handle: Rectangle {
anchors.centerIn: parent
color: qgcPal.button
border.color: qgcPal.buttonText
border.width: 1
implicitWidth: _radius * 2
implicitHeight: _radius * 2
radius: _radius
property real _radius: Math.round(ScreenTools.defaultFontPixelHeight * 0.75)
} }
} }
} }

1
src/QmlControls/ScreenTools.qml

@ -70,6 +70,7 @@ Item {
property real implicitTextFieldHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) property real implicitTextFieldHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6))
property real implicitComboBoxHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6)) property real implicitComboBoxHeight: Math.round(defaultFontPixelHeight * (isMobile ? 2.0 : 1.6))
property real implicitComboBoxWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0)) property real implicitComboBoxWidth: Math.round(defaultFontPixelWidth * (isMobile ? 7.0 : 5.0))
property real implicitSliderHeight: isMobile ? Math.Max(defaultFontPixelHeight, minTouchPixels) : defaultFontPixelHeight
readonly property string normalFontFamily: "opensans" readonly property string normalFontFamily: "opensans"
readonly property string demiboldFontFamily: "opensans-demibold" readonly property string demiboldFontFamily: "opensans-demibold"

6
src/QmlControls/SliderSwitch.qml

@ -8,8 +8,8 @@ import QGroundControl.Palette 1.0
/// control on an iPhone. /// control on an iPhone.
Rectangle { Rectangle {
id: _root id: _root
width: label.contentWidth + (_diameter * 2.5) + (_border * 4) implicitWidth: label.contentWidth + (_diameter * 2.5) + (_border * 4)
height: Math.max(ScreenTools.isMobile ? ScreenTools.minTouchPixels : 0, label.height * 2.5) implicitHeight: Math.max(ScreenTools.isMobile ? ScreenTools.minTouchPixels : 0, label.height * 2.5)
radius: height /2 radius: height /2
color: qgcPal.window color: qgcPal.window
@ -28,7 +28,7 @@ Rectangle {
id: label id: label
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
text: qsTr("Slide to %1").arg(confirmText) text: confirmText
} }
Rectangle { Rectangle {

14
src/Vehicle/Vehicle.cc

@ -1985,13 +1985,13 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
_firmwarePlugin->guidedModeGotoLocation(this, gotoCoord); _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
} }
void Vehicle::guidedModeChangeAltitude(double altitudeRel) void Vehicle::guidedModeChangeAltitude(double altitudeChange)
{ {
if (!guidedModeSupported()) { if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return; return;
} }
_firmwarePlugin->guidedModeChangeAltitude(this, altitudeRel); _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
} }
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude) void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
@ -2397,11 +2397,21 @@ QString Vehicle::missionFlightMode(void) const
return _firmwarePlugin->missionFlightMode(); return _firmwarePlugin->missionFlightMode();
} }
QString Vehicle::pauseFlightMode(void) const
{
return _firmwarePlugin->pauseFlightMode();
}
QString Vehicle::rtlFlightMode(void) const QString Vehicle::rtlFlightMode(void) const
{ {
return _firmwarePlugin->rtlFlightMode(); return _firmwarePlugin->rtlFlightMode();
} }
QString Vehicle::landFlightMode(void) const
{
return _firmwarePlugin->landFlightMode();
}
QString Vehicle::takeControlFlightMode(void) const QString Vehicle::takeControlFlightMode(void) const
{ {
return _firmwarePlugin->takeControlFlightMode(); return _firmwarePlugin->takeControlFlightMode();

9
src/Vehicle/Vehicle.h

@ -294,7 +294,9 @@ public:
Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged) Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged)
Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged) Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged)
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT) Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT) Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT) Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged) Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged) Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
@ -384,8 +386,9 @@ public:
/// Command vehicle to move to specified location (altitude is included and relative) /// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord); Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);
/// Command vehicle to change to the specified relatice altitude /// Command vehicle to change altitude
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeRel); /// @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange);
/// Command vehicle to orbit given center point /// Command vehicle to orbit given center point
/// @param centerCoord Center Coordinates /// @param centerCoord Center Coordinates
@ -575,7 +578,9 @@ public:
QString brandImageOutdoor () const; QString brandImageOutdoor () const;
QStringList unhealthySensors () const; QStringList unhealthySensors () const;
QString missionFlightMode () const; QString missionFlightMode () const;
QString pauseFlightMode () const;
QString rtlFlightMode () const; QString rtlFlightMode () const;
QString landFlightMode () const;
QString takeControlFlightMode () const; QString takeControlFlightMode () const;
double defaultCruiseSpeed () const { return _defaultCruiseSpeed; } double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
double defaultHoverSpeed () const { return _defaultHoverSpeed; } double defaultHoverSpeed () const { return _defaultHoverSpeed; }

Loading…
Cancel
Save