Commit 088c2d94 authored by Don Gagne's avatar Don Gagne

Starting point for new MultiVehicle view

parent badcdb6b
......@@ -34,6 +34,7 @@
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
<file alias="MultiVehicleView.qml">src/MultiVehicle/MultiVehicleView.qml</file>
<file alias="MotorComponent.qml">src/AutoPilotPlugins/Common/MotorComponent.qml</file>
<file alias="OfflineMap.qml">src/QtLocationPlugin/QMLControl/OfflineMap.qml</file>
<file alias="PowerComponent.qml">src/AutoPilotPlugins/PX4/PowerComponent.qml</file>
......@@ -45,6 +46,8 @@
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
<file alias="QGroundControl/Controls/FactSliderPanel.qml">src/QmlControls/FactSliderPanel.qml</file>
<file alias="QGroundControl/Controls/FlightModeDropdown.qml">src/QmlControls/FlightModeDropdown.qml</file>
<file alias="QGroundControl/Controls/GuidedBar.qml">src/QmlControls/GuidedBar.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
<file alias="QGroundControl/Controls/MainToolBar.qml">src/ui/toolbar/MainToolBar.qml</file>
......@@ -104,6 +107,7 @@
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewMap.qml">src/FlightDisplay/FlightDisplayViewMap.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewVideo.qml">src/FlightDisplay/FlightDisplayViewVideo.qml</file>
<file alias="QGroundControl/FlightDisplay/FlightDisplayViewWidgets.qml">src/FlightDisplay/FlightDisplayViewWidgets.qml</file>
<file alias="QGroundControl/FlightDisplay/MultiVehicleList.qml">src/FlightDisplay/MultiVehicleList.qml</file>
<file alias="QGroundControl/FlightDisplay/qmldir">src/FlightDisplay/qmldir</file>
<file alias="QGroundControl/FlightMap/CenterMapDropButton.qml">src/FlightMap/Widgets/CenterMapDropButton.qml</file>
<file alias="QGroundControl/FlightMap/FlightMap.qml">src/FlightMap/FlightMap.qml</file>
......
......@@ -762,3 +762,13 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return QString();
}
}
QString APMFirmwarePlugin::missionFlightMode(void)
{
return QStringLiteral("Auto");
}
QString APMFirmwarePlugin::rtlFlightMode(void)
{
return QStringLiteral("RTL");
}
......@@ -75,28 +75,30 @@ public:
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QList<MAV_CMD> supportedMissionCommands(void) final;
AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) final;
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities);
QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
bool isGuidedMode (const Vehicle* vehicle) const final;
void pauseVehicle (Vehicle* vehicle);
int manualControlReservedButtonCount(void);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYSID_SW_TYPE"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const;
QString getVersionParam (void) final { return QStringLiteral("SYSID_SW_MREV"); }
QString internalParameterMetaDataFile (Vehicle* vehicle) final;
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new APMGeoFenceManager(vehicle); }
RallyPointManager* newRallyPointManager (Vehicle* vehicle) { return new APMRallyPointManager(vehicle); }
QString brandImage (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) final;
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities);
QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
bool isGuidedMode (const Vehicle* vehicle) const final;
void pauseVehicle (Vehicle* vehicle);
int manualControlReservedButtonCount(void);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYSID_SW_TYPE"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const;
QString getVersionParam (void) final { return QStringLiteral("SYSID_SW_MREV"); }
QString internalParameterMetaDataFile (Vehicle* vehicle) final;
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new APMGeoFenceManager(vehicle); }
RallyPointManager* newRallyPointManager (Vehicle* vehicle) { return new APMRallyPointManager(vehicle); }
QString brandImage (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
QString missionFlightMode (void) final;
QString rtlFlightMode (void) final;
protected:
/// All access to singleton is through stack specific implementation
......
......@@ -204,3 +204,8 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
Q_UNUSED(vehicle);
return QStringLiteral("FENCE_RADIUS");
}
QString ArduCopterFirmwarePlugin::takeControlFlightMode(void)
{
return QStringLiteral("Stabilize");
}
......@@ -68,6 +68,7 @@ public:
bool multiRotorXConfig(Vehicle* vehicle) final;
QString geoFenceRadiusParam(Vehicle* vehicle) final;
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); }
QString takeControlFlightMode(void) final;
private:
static bool _remapParamNameIntialized;
......
......@@ -64,3 +64,8 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
supportedFlightModes << APMPlaneMode(APMPlaneMode::QRTL ,true);
setSupportedModes(supportedFlightModes);
}
QString ArduPlaneFirmwarePlugin::takeControlFlightMode(void)
{
return QStringLiteral("Manual");
}
......@@ -57,6 +57,7 @@ public:
// Overrides from FirmwarePlugin
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); }
QString takeControlFlightMode(void) final;
};
#endif
......@@ -282,3 +282,18 @@ int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumbe
Q_UNUSED(majorVersionNumber);
return 0;
}
QString FirmwarePlugin::missionFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::rtlFlightMode(void)
{
return QString();
}
QString FirmwarePlugin::takeControlFlightMode(void)
{
return QString();
}
......@@ -125,6 +125,15 @@ public:
/// Command vehicle to change to the specified relatice altitude
virtual void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel);
/// 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
/// not just this. I'm going to try to change that. If not, this will need to be removed.
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
......
......@@ -35,44 +35,42 @@ struct Modes2Name {
bool multiRotor; /// multi rotor compatible
};
const char* PX4FirmwarePlugin::manualFlightMode = "Manual";
const char* PX4FirmwarePlugin::altCtlFlightMode = "Altitude";
const char* PX4FirmwarePlugin::posCtlFlightMode = "Position";
const char* PX4FirmwarePlugin::missionFlightMode = "Mission";
const char* PX4FirmwarePlugin::holdFlightMode = "Hold";
const char* PX4FirmwarePlugin::takeoffFlightMode = "Takeoff";
const char* PX4FirmwarePlugin::landingFlightMode = "Land";
const char* PX4FirmwarePlugin::rtlFlightMode = "Return";
const char* PX4FirmwarePlugin::acroFlightMode = "Acro";
const char* PX4FirmwarePlugin::offboardFlightMode = "Offboard";
const char* PX4FirmwarePlugin::stabilizedFlightMode = "Stabilized";
const char* PX4FirmwarePlugin::rattitudeFlightMode = "Rattitude";
const char* PX4FirmwarePlugin::followMeFlightMode = "Follow Me";
const char* PX4FirmwarePlugin::rtgsFlightMode = "Return to Groundstation";
const char* PX4FirmwarePlugin::readyFlightMode = "Ready"; // unused
const char* PX4FirmwarePlugin::_manualFlightMode = "Manual";
const char* PX4FirmwarePlugin::_altCtlFlightMode = "Altitude";
const char* PX4FirmwarePlugin::_posCtlFlightMode = "Position";
const char* PX4FirmwarePlugin::_missionFlightMode = "Mission";
const char* PX4FirmwarePlugin::_holdFlightMode = "Hold";
const char* PX4FirmwarePlugin::_takeoffFlightMode = "Takeoff";
const char* PX4FirmwarePlugin::_landingFlightMode = "Land";
const char* PX4FirmwarePlugin::_rtlFlightMode = "Return";
const char* PX4FirmwarePlugin::_acroFlightMode = "Acro";
const char* PX4FirmwarePlugin::_offboardFlightMode = "Offboard";
const char* PX4FirmwarePlugin::_stabilizedFlightMode = "Stabilized";
const char* PX4FirmwarePlugin::_rattitudeFlightMode = "Rattitude";
const char* PX4FirmwarePlugin::_followMeFlightMode = "Follow Me";
const char* PX4FirmwarePlugin::_rtgsFlightMode = "Return to Groundstation";
const char* PX4FirmwarePlugin::_readyFlightMode = "Ready";
/// Tranlates from PX4 custom modes to flight mode names
static const struct Modes2Name rgModes2Name[] = {
//main_mode sub_mode name canBeSet FW MC
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::manualFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::stabilizedFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::acroFlightMode, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::rattitudeFlightMode, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::altCtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::posCtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, PX4FirmwarePlugin::holdFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, PX4FirmwarePlugin::missionFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, PX4FirmwarePlugin::rtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, PX4FirmwarePlugin::followMeFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::offboardFlightMode, true, true, true },
//main_mode sub_mode name canBeSet FW MC
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::_manualFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::_stabilizedFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::_acroFlightMode, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::_rattitudeFlightMode, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::_altCtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::_posCtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, PX4FirmwarePlugin::_holdFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, PX4FirmwarePlugin::_missionFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, PX4FirmwarePlugin::_rtlFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, PX4FirmwarePlugin::_followMeFlightMode, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::_offboardFlightMode, true, true, true },
// modes that can't be directly set by the user
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, PX4FirmwarePlugin::landingFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, PX4FirmwarePlugin::readyFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTGS, PX4FirmwarePlugin::rtgsFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF, PX4FirmwarePlugin::takeoffFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, PX4FirmwarePlugin::_landingFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, PX4FirmwarePlugin::_readyFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTGS, PX4FirmwarePlugin::_rtgsFlightMode, false, true, true },
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF, PX4FirmwarePlugin::_takeoffFlightMode, false, true, true },
};
PX4FirmwarePlugin::PX4FirmwarePlugin(void)
......@@ -297,12 +295,12 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle)
{
vehicle->setFlightMode(rtlFlightMode);
vehicle->setFlightMode(_rtlFlightMode);
}
void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
vehicle->setFlightMode(landingFlightMode);
vehicle->setFlightMode(_landingFlightMode);
}
void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
......@@ -388,7 +386,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
if (guidedMode) {
vehicle->setFlightMode(holdFlightMode);
vehicle->setFlightMode(_holdFlightMode);
} else {
pauseVehicle(vehicle);
}
......@@ -397,8 +395,8 @@ void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
// Not supported by generic vehicle
return (vehicle->flightMode() == holdFlightMode || vehicle->flightMode() == takeoffFlightMode
|| vehicle->flightMode() == landingFlightMode);
return (vehicle->flightMode() == _holdFlightMode || vehicle->flightMode() == _takeoffFlightMode
|| vehicle->flightMode() == _landingFlightMode);
}
bool PX4FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
......@@ -456,3 +454,18 @@ 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);
}
......@@ -60,25 +60,28 @@ public:
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new PX4GeoFenceManager(vehicle); }
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
QString brandImage (const Vehicle* vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
QString missionFlightMode (void) final;
QString rtlFlightMode (void) final;
QString takeControlFlightMode (void) final;
// NOTE: For internal use only. Do not use in mainline QGC code.
// Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the
// names may change.
static const char* manualFlightMode;
static const char* acroFlightMode;
static const char* stabilizedFlightMode;
static const char* rattitudeFlightMode;
static const char* altCtlFlightMode;
static const char* posCtlFlightMode;
static const char* offboardFlightMode;
static const char* readyFlightMode;
static const char* takeoffFlightMode;
static const char* holdFlightMode;
static const char* missionFlightMode;
static const char* rtlFlightMode;
static const char* landingFlightMode;
static const char* rtgsFlightMode;
static const char* followMeFlightMode;
static const char* _manualFlightMode;
static const char* _acroFlightMode;
static const char* _stabilizedFlightMode;
static const char* _rattitudeFlightMode;
static const char* _altCtlFlightMode;
static const char* _posCtlFlightMode;
static const char* _offboardFlightMode;
static const char* _readyFlightMode;
static const char* _takeoffFlightMode;
static const char* _holdFlightMode;
static const char* _missionFlightMode;
static const char* _rtlFlightMode;
static const char* _landingFlightMode;
static const char* _rtgsFlightMode;
static const char* _followMeFlightMode;
private:
void _handleAutopilotVersion(Vehicle* vehicle, mavlink_message_t* message);
......
......@@ -41,14 +41,15 @@ QGCView {
property real _pitch: _activeVehicle ? _activeVehicle.pitch.value : _defaultPitch
property real _heading: _activeVehicle ? _activeVehicle.heading.value : _defaultHeading
property Fact _emptyFact: Fact { }
property Fact _groundSpeedFact: _activeVehicle ? _activeVehicle.groundSpeed : _emptyFact
property Fact _airSpeedFact: _activeVehicle ? _activeVehicle.airSpeed : _emptyFact
property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false
property real _savedZoomLevel: 0
property real _savedZoomLevel: 0
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real pipSize: mainWindow.width * 0.2
......@@ -120,6 +121,8 @@ QGCView {
px4JoystickCheck()
}
QGCMapPalette { id: mapPal; lightColors: _mainIsMap ? _flightMap.isSatelliteMap : true }
QGCViewPanel {
id: _panel
anchors.fill: parent
......@@ -218,6 +221,33 @@ QGCView {
}
}
Row {
id: singleMultiSelector
anchors.topMargin: ScreenTools.toolbarHeight + _margins
anchors.rightMargin: _margins
anchors.right: parent.right
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelWidth
z: _panel.z + 4
visible: QGroundControl.multiVehicleManager.vehicles.count > 1
ExclusiveGroup { id: multiVehicleSelectorGroup }
QGCRadioButton {
id: singleVehicleView
exclusiveGroup: multiVehicleSelectorGroup
text: qsTr("Single")
checked: true
color: mapPal.text
}
QGCRadioButton {
exclusiveGroup: multiVehicleSelectorGroup
text: qsTr("Multi-Vehicle (WIP)")
color: mapPal.text
}
}
FlightDisplayViewWidgets {
id: flightDisplayViewWidgets
z: _panel.z + 4
......@@ -227,8 +257,20 @@ QGCView {
anchors.bottom: parent.bottom
qgcView: root
isBackgroundDark: root.isBackgroundDark
visible: singleVehicleView.checked
}
MultiVehicleList {
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
anchors.right: parent.right
anchors.bottom: parent.bottom
width: ScreenTools.defaultFontPixelWidth * 30
visible: !singleVehicleView.checked
z: _panel.z + 4
}
//-- Virtual Joystick
Loader {
id: virtualJoystickMultiTouch
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.4
import QtQuick.Controls 1.3
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.FlightMap 1.0
QGCListView {
id: missionItemEditorListView
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical
model: QGroundControl.multiVehicleManager.vehicles
cacheBuffer: _cacheBuffer < 0 ? 0 : _cacheBuffer
clip: true
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _cacheBuffer: height * 2
property real _widgetHeight: ScreenTools.defaultFontPixelHeight * 3
delegate: Rectangle {
width: parent.width
height: innerColumn.y + innerColumn.height + _margin
color: qgcPal.buttonHighlight
opacity: 0.8
radius: _margin
property var _vehicle: object
property color _textColor: "black"
QGCPalette { id: qgcPal }
Row {
id: widgetLayout
anchors.margins: _margin
anchors.top: parent.top
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth / 2
layoutDirection: Qt.RightToLeft
QGCCompassWidget {
size: _widgetHeight
active: true
heading: _vehicle.heading.rawValue
}
QGCAttitudeWidget {
size: _widgetHeight
active: true
rollAngle: _vehicle.roll.rawValue
pitchAngle: _vehicle.pitch.rawValue
}
}
RowLayout {
anchors.top: widgetLayout.top
anchors.bottom: widgetLayout.bottom
anchors.left: parent.left
anchors.right: widgetLayout.left
spacing: ScreenTools.defaultFontPixelWidth / 2
QGCLabel {
Layout.alignment: Qt.AlignTop
text: _vehicle.id
color: _textColor
}
QGCLabel {
text: _vehicle.flightMode
font.pointSize: ScreenTools.largeFontPointSize
color: _textColor
}
}
Column {
id: innerColumn
anchors.margins: _margin
anchors.left: parent.left
anchors.right: parent.right
anchors.top: widgetLayout.bottom
spacing: _margin
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: 5
color: "green"
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCButton {
text: "Arm"
visible: !_vehicle.armed
onClicked: _vehicle.armed = true
}
QGCButton {
text: "Start"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.missionFlightMode
onClicked: _vehicle.flightMode = _vehicle.missionFlightMode
}
QGCButton {
text: "Stop"
visible: _vehicle.armed && _vehicle.pauseVehicleSupported
onClicked: _vehicle.pauseVehicle()
}
QGCButton {
text: "RTL"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.rtlFlightMode
onClicked: _vehicle.flightMode = _vehicle.rtlFlightMode
}
QGCButton {
text: "Take control"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.takeControlFlightMode
onClicked: _vehicle.flightMode = _vehicle.takeControlFlightMode
}
}
}
}
} // QGCListView
......@@ -4,4 +4,5 @@ FlightDisplayView 1.0 FlightDisplayView.qml
FlightDisplayViewMap 1.0 FlightDisplayViewMap.qml
FlightDisplayViewVideo 1.0 FlightDisplayViewVideo.qml
FlightDisplayViewWidgets 1.0 FlightDisplayViewWidgets.qml
MultiVehicleList 1.0 MultiVehicleList.qml
......@@ -48,7 +48,19 @@ void GeoFenceController::start(bool editMode)
qCDebug(GeoFenceControllerLog) << "start editMode" << editMode;
PlanElementController::start(editMode);
_init();
}
void GeoFenceController::startStaticActiveVehicle(Vehicle* vehicle)
{
qCDebug(GeoFenceControllerLog) << "startStaticActiveVehicle";
PlanElementController::startStaticActiveVehicle(vehicle);
_init();
}
void GeoFenceController::_init(void)
{
connect(&_polygon, &QGCMapPolygon::dirtyChanged, this, &GeoFenceController::_polygonDirtyChanged);
}
......
......@@ -50,17 +50,18 @@ public:
Q_PROPERTY(bool breachReturnSupported READ breachReturnSupported NOTIFY breachReturnSupportedChanged)
#endif
void start (bool editMode) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
void loadFromFile (const QString& filename) final;
void saveToFilePicker (void) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
void loadFromFile (const QString& filename) final;
void saveToFilePicker (void) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
QString fileExtension(void) const final;
......@@ -96,6 +97,7 @@ private slots:
void _loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
private:
void _init(void);
void _signalAll(void);
bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString);
......
......@@ -66,7 +66,19 @@ void MissionController::start(bool editMode)
qCDebug(MissionControllerLog) << "start editMode" << editMode;
PlanElementController::start(editMode);
_init();
}
void MissionController::startStaticActiveVehicle(Vehicle *vehicle)
{
qCDebug(MissionControllerLog) << "startStaticActiveVehicle";
PlanElementController::startStaticActiveVehicle(vehicle);
_init();
}
void MissionController::_init(void)
{
// We start with an empty mission
_visualItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_visualItems, false /* addToCenter */);
......
......@@ -57,17 +57,18 @@ public:
Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i);
// Overrides from PlanElementController
void start (bool editMode) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
void loadFromFile (const QString& filename) final;
void saveToFilePicker (void) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
void loadFromFile (const QString& filename) final;
void saveToFilePicker (void) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
QString fileExtension(void) const final;
......@@ -112,6 +113,7 @@ private slots:
void _homeCoordinateChanged(void);
private:
void _init(void);
void _recalcSequence(void);
void _recalcChildItems(void);
void _recalcAll(void);
......
......@@ -32,6 +32,12 @@ void PlanElementController::start(bool editMode)
_activeVehicleChanged(_multiVehicleMgr->activeVehicle());
}
void PlanElementController::startStaticActiveVehicle(Vehicle* vehicle)
{
_editMode = false;
_activeVehicleChanged(vehicle);
}
void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle)
{
if (_activeVehicle) {
......
......@@ -39,6 +39,10 @@ public:
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE virtual void start(bool editMode);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE virtual void startStaticActiveVehicle(Vehicle* vehicle);
Q_INVOKABLE virtual void loadFromVehicle(void) = 0;
Q_INVOKABLE virtual void sendToVehicle(void) = 0;
Q_INVOKABLE virtual void loadFromFilePicker(void) = 0;
......
......@@ -46,13 +46,6 @@ RallyPointController::~RallyPointController()
}
void RallyPointController::start(bool editMode)
{
qCDebug(RallyPointControllerLog) << "start editMode" << editMode;
PlanElementController::start(editMode);
}
void RallyPointController::_activeVehicleBeingRemoved(void)
{
_activeVehicle->rallyPointManager()->disconnect(this);
......
......@@ -37,7 +37,6 @@ public:
Q_INVOKABLE void addPoint(QGeoCoordinate point);
Q_INVOKABLE void removePoint(QObject* rallyPoint);
void start (bool editMode) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFilePicker (void) final;
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.4
import QtQuick.Controls 1.3
import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
/// Multi-Vehicle View
QGCView {
id: qgcView
viewPanel: panel
property real _margins: ScreenTools.defaultFontPixelWidth
property var _fileDialogController
readonly property string _loadingText: qsTr("Loading...")
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
QGCViewPanel {
id: panel
anchors.fill: parent
Rectangle {
anchors.fill: parent
color: qgcPal.window
QGCFlickable {
anchors.fill: parent
contentHeight: vehicleColumn.height
flickableDirection: Flickable.VerticalFlick
clip: true
Column {
id: vehicleColumn
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
spacing: _margins
QGCLabel { text: qsTr("All Vehicles") }
Repeater {
model: QGroundControl.multiVehicleManager.vehicles
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight / 2
MissionController {
id: missionController
Component.onCompleted: startStaticActiveVehicle(object)
property bool missionAvailable: visualItems && visualItems.count > 1
function loadFromSelectedFile() {
if (ScreenTools.isMobile) {
_fileDialogController = missionController
qgcView.showDialog(mobileFilePicker, qsTr("Select Mission File"), qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else {
missionController.loadFromFilePicker()
missionController.sendToVehicle()
}
}
} // MissionController
GeoFenceController {
id: geoFenceController
Component.onCompleted: startStaticActiveVehicle(object)
property bool fenceAvailable: fenceSupported && (circleSupported || polygonSupported)
function loadFromSelectedFile() {
if (ScreenTools.isMobile) {
_fileDialogController = geoFenceController
qgcView.showDialog(mobileFilePicker, qsTr("Select Fence File"), qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else {
geoFenceController.loadFromFilePicker()
geoFenceController.sendToVehicle()
}
}
} // GeoFenceController
RallyPointController {
id: rallyPointController
Component.onCompleted: startStaticActiveVehicle(object)
property bool pointsAvailable: rallyPointsSupported && points.count
function loadFromSelectedFile() {
if (ScreenTools.isMobile) {
_fileDialogController = rallyPointController
qgcView.showDialog(mobileFilePicker, qsTr("Select Rally Point File"), qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else {
rallyPointController.loadFromFilePicker()
rallyPointController.sendToVehicle()
}
}
} // RallyPointController
QGCLabel {
text: "Vehicle #" + object.id
}
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: vehicleDisplayColumn.height + (_margins * 2)
color: qgcPal.windowShade
Column {
id: vehicleDisplayColumn
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
Row {
id: indicatorRow
spacing: _margins
visible: !object.connectionLost
Rectangle {
width: missionLabel.contentWidth + _margins
height: ScreenTools.defaultFontPixelHeight + _margins
radius: height / 4
color: missionController.missionAvailable ? "green" : qgcPal.window
border.width: 1
border.color: qgcPal.text
QGCLabel {
id: missionLabel
anchors.margins: _margins / 2
anchors.left: parent.left
anchors.top: parent.top
text: missionController.syncInProgress ? _loadingText : qsTr("Mission")
}
MouseArea {
anchors.fill: parent
enabled: !missionController.syncInProgress
onClicked: missionController.loadFromSelectedFile()
}
}
Rectangle {
width: fenceLabel.contentWidth + _margins
height: ScreenTools.defaultFontPixelHeight + _margins
radius: height / 4
color: geoFenceController.fenceAvailable ? "green" : qgcPal.window
border.width: 1
border.color: qgcPal.text
QGCLabel {
id: fenceLabel
anchors.margins: _margins / 2
anchors.left: parent.left
anchors.top: parent.top
text: geoFenceController.syncInProgress ? _loadingText : qsTr("Fence")
}
MouseArea {
anchors.fill: parent
enabled: !geoFenceController.syncInProgress
onClicked: geoFenceController.loadFromSelectedFile()
}
}
Rectangle {
width: rallyLabel.contentWidth + _margins
height: ScreenTools.defaultFontPixelHeight + _margins
radius: height / 4
color: rallyPointController.pointsAvailable ? "green" : qgcPal.window
border.width: 1
border.color: qgcPal.text
QGCLabel {
id: rallyLabel
anchors.margins: _margins / 2
anchors.left: parent.left
anchors.top: parent.top
text: rallyPointController.syncInProgress ? _loadingText : qsTr("Rally")
}
MouseArea {
anchors.fill: parent
enabled: !rallyPointController.syncInProgress
onClicked: rallyPointController.loadFromSelectedFile()
}
}
FlightModeDropdown { activeVehicle: object }
GuidedBar { activeVehicle: object }
} // Row - contents display
Flow {
anchors.left: parent.left
anchors.right: parent.right
layoutDirection: Qt.LeftToRight
spacing: _margins
Repeater {
model: [ "battery.voltage", "battery.percentRemaining", "altitudeRelative", "altitudeAMSL", "groundSpeed", "heading"]
Column {
property Fact fact: object.getFact(modelData)
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: fact.shortDescription
}
Row {
anchors.horizontalCenter: parent.horizontalCenter
//spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
text: fact.enumOrValueString
}
QGCLabel {
text: fact.units
}
}
}
} // Repeater - Small
} // Flow
} // Column
} // Rectangle - contents display
} // Column - layout for vehicle
} // Repeater - vehicle repeater
} // Column
} // QGCFlickable
} // Rectangle - View background
} // QGCViewPanel
Component {
id: mobileFilePicker
QGCMobileFileDialog {
openDialog: true
fileExtension: _fileDialogController.fileExtension
onFilenameReturned: {
_fileDialogController.loadFromFile(filename)
_fileDialogController.sendToVehicle()
}
}
}
} // QGCView
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.5
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Item {
width: flightModeLabel.visible ? flightModeLabel.width : flightModeCombo.width
height: flightModeLabel.visible ? flightModeLabel.height : flightModeCombo.height
property var activeVehicle ///< Vehicle to show flight modes for
property int _maxFMCharLength: 10 ///< Maximum number of chars in a flight mode
property string flightMode: activeVehicle ? activeVehicle.flightMode : qsTr("N/A", "No data to display")
onActiveVehicleChanged: _activeVehicleChanged()
onFlightModeChanged: {
if (flightModeCombo.visible) {
flightModeCombo.currentIndex = flightModeCombo.find(flightMode)
}
}
Component.onCompleted: _activeVehicleChanged()
function _activeVehicleChanged() {
if (activeVehicle.flightModeSetAvailable) {
var maxFMChars = 0
for (var i=0; i<activeVehicle.flightModes.length; i++) {
maxFMChars = Math.max(maxFMChars, activeVehicle.flightModes[i].length)
}
_maxFMCharLength = maxFMChars
}
}
QGCLabel {
id: flightModeLabel
text: flightMode
visible: !activeVehicle.flightModeSetAvailable
anchors.verticalCenter: parent.verticalCenter
}
QGCComboBox {
id: flightModeCombo
width: (_maxFMCharLength + 4) * ScreenTools.defaultFontPixelWidth
model: activeVehicle ? activeVehicle.flightModes : 0
visible: activeVehicle.flightModeSetAvailable
onModelChanged: {
if (activeVehicle && visible) {
currentIndex = find(flightMode)
}
}
onActivated: activeVehicle.flightMode = textAt(index)
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.5
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
//-- Guided mode bar
Rectangle {
id: guidedModeBar
width: guidedModeColumn.width + (_margins * 2)
height: guidedModeColumn.height + (_margins * 2)
radius: ScreenTools.defaultFontPixelHeight * 0.25
color: backgroundColor
property var activeVehicle ///< Vehicle to show guided bar for
property real fontPointSize: ScreenTools.defaultFontPointSize ///< point size for fonts in control
property color backgroundColor: qgcPal.windowShadeDark ///< Background color for bar
// Values for _confirmActionCode
readonly property int confirmHome: 1
readonly property int confirmLand: 2
readonly property int confirmTakeoff: 3
readonly property int confirmArm: 4
readonly property int confirmDisarm: 5
readonly property int confirmEmergencyStop: 6
readonly property int confirmChangeAlt: 7
readonly property int confirmGoTo: 8
readonly property int confirmRetask: 9
readonly property int confirmOrbit: 10
property int _confirmActionCode
property real _showMargin: _margins
property real _hideMargin: _margins - guidedModeBar.height
property real _barMargin: _showMargin
property bool _showConfirm: false
property string _confirmText
property bool _showAltitude: false
property real _confirmAltitude
function actionConfirmed(altitude) {
_showConfirm = false
switch (_confirmActionCode) {
case confirmHome:
activeVehicle.guidedModeRTL()
break;
case confirmLand:
activeVehicle.guidedModeLand()
break;
case confirmTakeoff:
activeVehicle.guidedModeTakeoff(altitude)
break;
case confirmArm:
activeVehicle.armed = true
break;
case confirmDisarm:
activeVehicle.armed = false
break;
case confirmEmergencyStop:
activeVehicle.emergencyStop()
break;
case confirmChangeAlt:
activeVehicle.guidedModeChangeAltitude(altitude)
break;
case confirmGoTo:
activeVehicle.guidedModeGotoLocation(_flightMap._gotoHereCoordinate)
break;
case confirmRetask:
activeVehicle.setCurrentMissionSequence(_flightMap._retaskSequence)
break;
case confirmOrbit:
//-- All parameters controlled by RC
activeVehicle.guidedModeOrbit()
//-- Center on current flight map position and orbit with a 50m radius (velocity/direction controlled by the RC)
//activeVehicle.guidedModeOrbit(QGroundControl.flightMapPosition, 50.0)
break;
default:
console.warn(qsTr("Internal error: unknown _confirmActionCode"), _confirmActionCode)
}
}
function actionRejected() {
_showConfirm = false
/*
altitudeSlider.visible = false
_flightMap._gotoHereCoordinate = QtPositioning.coordinate()
guidedModeHideTimer.restart()
*/
}
function confirmAction(actionCode) {
//guidedModeHideTimer.stop()
_confirmActionCode = actionCode
_showAltitude = false
switch (_confirmActionCode) {
case confirmArm:
_confirmText = qsTr("Arm vehicle?")
break;
case confirmDisarm:
_confirmText = qsTr("Disarm vehicle?")
break;
case confirmEmergencyStop:
_confirmText = qsTr("STOP ALL MOTORS?")
break;
case confirmTakeoff:
_showAltitude = true
setInitialValueMeters(3)
_confirmText = qsTr("Takeoff vehicle?")
break;
case confirmLand:
_confirmText = qsTr("Land vehicle?")
break;
case confirmHome:
_confirmText = qsTr("Return to land?")
break;
case confirmChangeAlt:
_showAltitude = true
setInitialValueAppSettingsDistanceUnits(activeVehicle.altitudeRelative.value)
_confirmText = qsTr("Change altitude?")
break;
case confirmGoTo:
_confirmText = qsTr("Move vehicle?")
break;
case confirmRetask:
_confirmText = qsTr("Change active waypoint?")
break;
case confirmOrbit:
_confirmText = qsTr("Enter orbit mode?")
break;
}
_showConfirm = true
}
function setInitialValueMeters(meters) {
_confirmAltitude = QGroundControl.metersToAppSettingsDistanceUnits(meters)
}
function setInitialValueAppSettingsDistanceUnits(height) {
_confirmAltitude = height
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
Column {
id: guidedModeColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
/*
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
color: _lightWidgetBorders ? qgcPal.mapWidgetBorderDark : qgcPal.mapWidgetBorderLight
text: "Click in map to move vehicle"
visible: gotoEnabled
}*/
Row {
spacing: _margins * 2
visible: !_showConfirm
QGCButton {
pointSize: fontPointSize
text: (activeVehicle && activeVehicle.armed) ? (activeVehicle.flying ? qsTr("Emergency Stop") : qsTr("Disarm")) : qsTr("Arm")
visible: activeVehicle
onClicked: confirmAction(activeVehicle.armed ? (activeVehicle.flying ? confirmEmergencyStop : confirmDisarm) : confirmArm)
}
QGCButton {
pointSize: fontPointSize
text: qsTr("RTL")
visible: (activeVehicle && activeVehicle.armed) && activeVehicle.guidedModeSupported && activeVehicle.flying
onClicked: confirmAction(confirmHome)
}
QGCButton {
pointSize: fontPointSize
text: (activeVehicle && activeVehicle.flying) ? qsTr("Land"): qsTr("Takeoff")
visible: activeVehicle && activeVehicle.guidedModeSupported && activeVehicle.armed
onClicked: confirmAction(activeVehicle.flying ? confirmLand : confirmTakeoff)
}
QGCButton {
pointSize: fontPointSize
text: qsTr("Pause")
visible: (activeVehicle && activeVehicle.armed) && activeVehicle.pauseVehicleSupported && activeVehicle.flying
onClicked: {
guidedModeHideTimer.restart()
activeVehicle.pauseVehicle()
}
}
QGCButton {
pointSize: fontPointSize
text: qsTr("Change Altitude")
visible: (activeVehicle && activeVehicle.flying) && activeVehicle.guidedModeSupported && activeVehicle.armed
onClicked: confirmAction(confirmChangeAlt)
}
QGCButton {
pointSize: fontPointSize
text: qsTr("Orbit")
visible: (activeVehicle && activeVehicle.flying) && activeVehicle.orbitModeSupported && activeVehicle.armed
onClicked: confirmAction(confirmOrbit)
}
} // Row
Column {
visible: _showConfirm
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: _confirmText
}
Row {
anchors.horizontalCenter: parent.horizontalCenter
spacing: ScreenTools.defaultFontPixelWidth
Row {
visible: _showAltitude
QGCLabel {
text: qsTr("Alt (rel)")
}
QGCLabel {
text: QGroundControl.appSettingsDistanceUnitsString
}
QGCTextField {
id: altField
text: _confirmAltitude.toFixed(1)
}
}
QGCButton {
text: qsTr("Yes")
onClicked: {
var value = parseFloat(altField.text)
if (isNaN(value)) {
actionRejected()
} else {
actionConfirmed(QGroundControl.appSettingsDistanceUnitsToMeters(value))
}
}
}
QGCButton {
text: qsTr("No")
onClicked: actionRejected()
}
}
} // Column
} // Column
} // Rectangle - Guided mode buttons
......@@ -6,6 +6,8 @@ ClickableColor 1.0 ClickableColor.qml
DropButton 1.0 DropButton.qml
ExclusiveGroupItem 1.0 ExclusiveGroupItem.qml
FactSliderPanel 1.0 FactSliderPanel.qml
FlightModeDropdown 1.0 FlightModeDropdown.qml
GuidedBar 1.0 GuidedBar.qml
IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml
MainToolBar 1.0 MainToolBar.qml
......
......@@ -47,6 +47,7 @@ Item {
property real largeFontPointSize: 10
property real availableHeight: 0
property real toolbarHeight: defaultFontPixelHeight * 3
readonly property real smallFontPointRatio: 0.75
readonly property real mediumFontPointRatio: 1.25
......
......@@ -1346,6 +1346,8 @@ void Vehicle::setFlightMode(const QString& flightMode)
uint8_t base_mode;
uint32_t custom_mode;
qDebug() << flightMode;
if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) {
// setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
// states.
......@@ -2149,6 +2151,21 @@ void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
_firmwarePluginInstanceData = firmwarePluginInstanceData;
}
QString Vehicle::missionFlightMode(void) const
{
return _firmwarePlugin->missionFlightMode();
}
QString Vehicle::rtlFlightMode(void) const
{
return _firmwarePlugin->rtlFlightMode();
}
QString Vehicle::takeControlFlightMode(void) const
{
return _firmwarePlugin->takeControlFlightMode();
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
......
......@@ -271,6 +271,9 @@ public:
Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
Q_PROPERTY(QString brandImage READ brandImage CONSTANT)
Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged)
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged)
......@@ -522,6 +525,9 @@ public:
bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
QString brandImage () const;
QStringList unhealthySensors () const;
QString missionFlightMode () const;
QString rtlFlightMode () const;
QString takeControlFlightMode () const;
Fact* roll (void) { return &_rollFact; }
Fact* heading (void) { return &_headingFact; }
......
......@@ -255,7 +255,7 @@ Item {
MainToolBar {
id: toolBar
height: ScreenTools.defaultFontPixelHeight * 3
height: ScreenTools.toolbarHeight
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
......
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