Commit 552bdfba authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'mavlink/master' into telemetryData

* mavlink/master:
  Removing unused Main Flight Display widget.
  Start logging on heartbeat instead of connect
  Correct for relativeAlt, !relativeAlt, homePositionValid mix
  Fix relative altitude fact
  Calculate/Display distance between waypoints
parents 51e20d58 6fcdb317
......@@ -218,7 +218,6 @@ HEADERS += \
src/comm/QGCMAVLink.h \
src/comm/TCPLink.h \
src/comm/UDPLink.h \
src/FlightDisplay/FlightDisplayWidget.h \
src/FlightDisplay/FlightDisplayViewController.h \
src/FlightMap/FlightMapSettings.h \
src/GAudioOutput.h \
......@@ -336,7 +335,6 @@ SOURCES += \
src/comm/MockLinkMissionItemHandler.cc \
src/comm/TCPLink.cc \
src/comm/UDPLink.cc \
src/FlightDisplay/FlightDisplayWidget.cc \
src/FlightDisplay/FlightDisplayViewController.cc \
src/FlightMap/FlightMapSettings.cc \
src/GAudioOutput.cc \
......
......@@ -47,10 +47,8 @@
<file alias="buttonLeft.svg">src/FlightMap/Images/buttonLeft.svg</file>
<file alias="buttonMore.svg">src/FlightMap/Images/buttonMore.svg</file>
<file alias="buttonRight.svg">src/FlightMap/Images/buttonRight.svg</file>
<file alias="compass.svg">src/FlightMap/Images/compass.svg</file>
<file alias="compassInstrumentAirplane.svg">src/FlightMap/Images/compassInstrumentAirplane.svg</file>
<file alias="compassInstrumentDial.svg">src/FlightMap/Images/compassInstrumentDial.svg</file>
<file alias="compassNeedle.svg">src/FlightMap/Images/compassNeedle.svg</file>
<file alias="crossHair.svg">src/FlightMap/Images/crossHair.svg</file>
<file alias="rollDialWhite.svg">src/FlightMap/Images/rollDialWhite.svg</file>
<file alias="rollPointerWhite.svg">src/FlightMap/Images/rollPointerWhite.svg</file>
......
......@@ -75,7 +75,6 @@
<file alias="AirframeComponent.qml">src/AutoPilotPlugins/PX4/AirframeComponent.qml</file>
<file alias="MainToolBar.qml">src/ui/toolbar/MainToolBar.qml</file>
<file alias="FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file>
<file alias="FlightDisplayWidget.qml">src/FlightDisplay/FlightDisplayWidget.qml</file>
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<file alias="MissionEditorHelp.qml">src/MissionEditor/MissionEditorHelp.qml</file>
......@@ -90,18 +89,13 @@
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
<file alias="QGroundControl/FlightMap/FlightMap.qml">src/FlightMap/FlightMap.qml</file>
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/QGCAltitudeWidget.qml">src/FlightMap/Widgets/QGCAltitudeWidget.qml</file>
<file alias="QGroundControl/FlightMap/QGCArtificialHorizon.qml">src/FlightMap/Widgets/QGCArtificialHorizon.qml</file>
<file alias="QGroundControl/FlightMap/QGCAttitudeWidget.qml">src/FlightMap/Widgets/QGCAttitudeWidget.qml</file>
<file alias="QGroundControl/FlightMap/QGCAttitudeHUD.qml">src/FlightMap/Widgets/QGCAttitudeHUD.qml</file>
<file alias="QGroundControl/FlightMap/QGCCompassWidget.qml">src/FlightMap/Widgets/QGCCompassWidget.qml</file>
<file alias="QGroundControl/FlightMap/QGCCompassHUD.qml">src/FlightMap/Widgets/QGCCompassHUD.qml</file>
<file alias="QGroundControl/FlightMap/QGCCurrentAltitude.qml">src/FlightMap/Widgets/QGCCurrentAltitude.qml</file>
<file alias="QGroundControl/FlightMap/QGCCurrentSpeed.qml">src/FlightMap/Widgets/QGCCurrentSpeed.qml</file>
<file alias="QGroundControl/FlightMap/QGCInstrumentWidget.qml">src/FlightMap/Widgets/QGCInstrumentWidget.qml</file>
<file alias="QGroundControl/FlightMap/QGCPitchIndicator.qml">src/FlightMap/Widgets/QGCPitchIndicator.qml</file>
<file alias="QGroundControl/FlightMap/QGCSlider.qml">src/FlightMap/Widgets/QGCSlider.qml</file>
<file alias="QGroundControl/FlightMap/QGCSpeedWidget.qml">src/FlightMap/Widgets/QGCSpeedWidget.qml</file>
<file alias="QGroundControl/FlightMap/MissionItemIndicator.qml">src/FlightMap/MapItems/MissionItemIndicator.qml</file>
<file alias="QGroundControl/FlightMap/VehicleMapItem.qml">src/FlightMap/MapItems/VehicleMapItem.qml</file>
<file alias="QGroundControl/FlightMap/MissionItemView.qml">src/FlightMap/MapItems/MissionItemView.qml</file>
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include <QQmlContext>
#include <QQmlEngine>
#include <QSettings>
#include <VideoItem.h>
#include <VideoSurface.h>
#include "VideoReceiver.h"
#include "ScreenToolsController.h"
#include "FlightDisplayWidget.h"
const char* kMainFlightDisplayWidgetGroup = "FlightDisplayWidget";
FlightDisplayWidget::FlightDisplayWidget(const QString& title, QAction* action, QWidget *parent)
: QGCQmlWidgetHolder(title, action, parent)
{
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
setObjectName("FlightDisplayWidget");
// Get rid of layout default margins
QLayout* pl = layout();
if(pl) {
pl->setContentsMargins(0,0,0,0);
}
setMinimumWidth(300);
setMinimumHeight(300);
setContextPropertyObject("flightDisplay", this);
/*
* This is the receiving end of an UDP RTP stream. The sender can be setup with this command:
*
* gst-launch-1.0 uvch264src initial-bitrate=1000000 average-bitrate=1000000 iframe-period=1000 name=src auto-start=true src.vidsrc ! \
* video/x-h264,width=1280,height=720,framerate=24/1 ! h264parse ! rtph264pay ! udpsink host=192.168.1.9 port=5000
*
* Where the main parameters are:
*
* uvch264src: Your h264 video source (the example above uses a Logitech C920 on an Raspberry PI 2+ or Odroid C1
* host=192.168.1.9 This is the IP address of QGC. You can use Avahi/Zeroconf to find QGC using the "_qgroundcontrol._udp" service.
*
* Advanced settings (you should probably read the gstreamer documentation before changing these):
*
* initial-bitrate=1000000 average-bitrate=1000000
* The bit rate to use. The greater, the better quality at the cost of higher bandwidth.
*
* width=1280,height=720,framerate=24/1
* The video resolution and frame rate. This depends on the camera used.
*
* iframe-period=1000
* Interval between iFrames. The greater the interval the lesser bandwidth at the cost of a longer time to recover from lost packets.
*
* Do not change anything else unless you know what you are doing. Any other change will require a matching change on the receiving end.
*
*/
VideoSurface* pSurface = new VideoSurface;
setContextPropertyObject("videoDisplay", pSurface);
VideoReceiver* pReceiver = new VideoReceiver(this);
pReceiver->setUri(QLatin1Literal("udp://0.0.0.0:5000"));
#if defined(QGC_GST_STREAMING)
pReceiver->setVideoSink(pSurface->videoSink());
#endif
setContextPropertyObject("videoReceiver", pReceiver);
setSource(QUrl::fromUserInput("qrc:/qml/FlightDisplayWidget.qml"));
setVisible(true);
loadSettings();
}
FlightDisplayWidget::~FlightDisplayWidget()
{
}
void FlightDisplayWidget::saveSetting(const QString &name, const QString& value)
{
QSettings settings;
QString key(kMainFlightDisplayWidgetGroup);
key += "/" + name;
settings.setValue(key, value);
}
QString FlightDisplayWidget::loadSetting(const QString &name, const QString& defaultValue)
{
QSettings settings;
QString key(kMainFlightDisplayWidgetGroup);
key += "/" + name;
return settings.value(key, defaultValue).toString();
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef FlightDisplayWidget_H
#define FlightDisplayWidget_H
#include "QGCQmlWidgetHolder.h"
class FlightDisplayWidget : public QGCQmlWidgetHolder
{
Q_OBJECT
public:
FlightDisplayWidget(const QString& title, QAction* action, QWidget* parent = NULL);
~FlightDisplayWidget();
/// @brief Invokes the Flight Display Options menu
void showOptionsMenu() { emit showOptionsMenuChanged(); }
Q_PROPERTY(bool hasVideo READ hasVideo CONSTANT)
Q_INVOKABLE void saveSetting (const QString &key, const QString& value);
Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue);
#if defined(QGC_GST_STREAMING)
bool hasVideo () { return true; }
#else
bool hasVideo () { return false; }
#endif
signals:
void showOptionsMenuChanged ();
};
#endif
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
import QtQuick 2.4
import QtQuick.Controls 1.3
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
/// Flight Display Widget
Item {
id: root
property var __qgcPal: QGCPalette { colorGroupEnabled: enabled }
property var activeVehicle: multiVehicleManager.activeVehicle
readonly property real defaultLatitude: 37.803784
readonly property real defaultLongitude: -122.462276
readonly property real defaultRoll: 0
readonly property real defaultPitch: 0
readonly property real defaultHeading: 0
readonly property real defaultAltitudeWGS84: 0
readonly property real defaultGroundSpeed: 0
readonly property real defaultAirSpeed: 0
readonly property real defaultClimbRate: 0
property real roll: activeVehicle ? (isNaN(activeVehicle.roll) ? defaultRoll : activeVehicle.roll) : defaultRoll
property real pitch: activeVehicle ? (isNaN(activeVehicle.pitch) ? defaultPitch : activeVehicle.pitch) : defaultPitch
property real latitude: activeVehicle ? ((activeVehicle.latitude === 0) ? defaultLatitude : activeVehicle.latitude) : defaultLatitude
property real longitude: activeVehicle ? ((activeVehicle.longitude === 0) ? defaultLongitude : activeVehicle.longitude) : defaultLongitude
property real heading: activeVehicle ? (isNaN(activeVehicle.heading) ? defaultHeading : activeVehicle.heading) : defaultHeading
property real altitudeWGS84: activeVehicle ? activeVehicle.altitudeWGS84 : defaultAltitudeWGS84
property real groundSpeed: activeVehicle ? activeVehicle.groundSpeed : defaultGroundSpeed
property real airSpeed: activeVehicle ? activeVehicle.airSpeed : defaultAirSpeed
property real climbRate: activeVehicle ? activeVehicle.climbRate : defaultClimbRate
property bool showPitchIndicator: true
function getBool(value) {
return value === '0' ? false : true;
}
function setBool(value) {
return value ? "1" : "0";
}
function enforceExclusiveOption(setWidget, alternateWidget, defaultSetting, alternateSetting) {
setWidget.visible = !setWidget.visible;
flightDisplay.saveSetting(defaultSetting, setBool(setWidget.visible));
alternateWidget.visible = setWidget.visible ? false : alternateWidget.visible;
flightDisplay.saveSetting(alternateSetting, setBool(alternateWidget.visible));
}
Connections {
target: flightDisplay
onShowOptionsMenuChanged: {
contextMenu.popup();
}
}
Component.onCompleted:
{
videoBackground.visible = getBool(flightDisplay.loadSetting("showVideoBackground", "0"));
// Disable video if we don't have support for it
if(!flightDisplay.hasVideo) {
videoBackground.visible = false;
flightDisplay.saveSetting("showVideoBackground", setBool(videoBackground.visible));
}
// Enable/Disable menu accordingly
videoMenu.enabled = flightDisplay.hasVideo;
}
Menu {
id: contextMenu
MenuItem {
id: videoMenu
text: "Video Background"
checkable: true
checked: videoBackground.visible
onToggled: videoBackground.visible = checked
}
}
// Video and Map backgrounds are exclusive. If one is enabled the other is disabled.
QGCVideoBackground {
id: videoBackground
anchors.fill: parent
display: videoDisplay
receiver: videoReceiver
z: 10
}
// HUD (lower middle) Compass
QGCCompassHUD {
id: compassHUD
y: root.height * 0.7
x: root.width * 0.5 - ScreenTools.defaultFontPixelSize * (5)
width: ScreenTools.defaultFontPixelSize * (10)
height: ScreenTools.defaultFontPixelSize * (10)
heading: root.heading
active: multiVehicleManager.activeVehicleAvailable
z: 70
}
// Sky/Ground background (visible when no Map or Video is enabled)
QGCArtificialHorizon {
id: artificialHoriz
anchors.fill: parent
rollAngle: roll
pitchAngle: pitch
visible: !videoBackground.visible
}
// HUD (center) Attitude Indicator
QGCAttitudeHUD {
id: attitudeHUD
rollAngle: roll
pitchAngle: pitch
showPitch: showPitchIndicator
width: ScreenTools.defaultFontPixelSize * (30)
height: ScreenTools.defaultFontPixelSize * (30)
active: multiVehicleManager.activeVehicleAvailable
z: 20
}
QGCAltitudeWidget {
id: altitudeWidget
anchors.right: parent.right
width: ScreenTools.defaultFontPixelSize * (5)
height: parent.height * 0.65 > ScreenTools.defaultFontPixelSize * (23.4) ? ScreenTools.defaultFontPixelSize * (23.4) : parent.height * 0.65
altitude: root.altitudeWGS84
z: 30
}
QGCSpeedWidget {
id: speedWidget
anchors.left: parent.left
width: ScreenTools.defaultFontPixelSize * (5)
height: parent.height * 0.65 > ScreenTools.defaultFontPixelSize * (23.4) ? ScreenTools.defaultFontPixelSize * (23.4) : parent.height * 0.65
speed: root.groundSpeed
z: 40
}
QGCCurrentSpeed {
id: currentSpeed
anchors.left: parent.left
width: ScreenTools.defaultFontPixelSize * (6.25)
airspeed: root.airSpeed
groundspeed: root.groundSpeed
active: multiVehicleManager.activeVehicleAvailable
showAirSpeed: true
showGroundSpeed: true
visible: (currentSpeed.showGroundSpeed || currentSpeed.showAirSpeed)
z: 50
}
QGCCurrentAltitude {
id: currentAltitude
anchors.right: parent.right
width: ScreenTools.defaultFontPixelSize * (6.25)
altitude: root.altitudeWGS84
vertZ: root.climbRate
showAltitude: true
showClimbRate: true
active: multiVehicleManager.activeVehicleAvailable
visible: (currentAltitude.showAltitude || currentAltitude.showClimbRate)
z: 60
}
QGCButton {
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.right: parent.right
anchors.bottom: parent.bottom
text: "Options"
menu: contextMenu
}
}
This diff is collapsed.
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 158.4" enable-background="new 0 0 288 158.4" xml:space="preserve">
<polygon points="279,7.2 144,151.2 9,7.2 "/>
</svg>
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief QGC Altitude Indicator
* @author Gus Grubba <mavlink@grubba.com>
*/
import QtQuick 2.4
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Rectangle {
id: root
property real altitude: 50
property real _reticleSpacing: ScreenTools.defaultFontPixelSize * (1.33)
property real _reticleHeight: ScreenTools.defaultFontPixelSize * (0.166)
property real _reticleSlot: _reticleSpacing + _reticleHeight
property var _speedArray: []
property int _currentCenter: 0
property int _currentStart: -100
function updateArray() {
var tmpArray = [];
_currentCenter = Math.floor(altitude / 5) * 5;
_currentStart = _currentCenter + 100;
for(var i = 0; i < 40; i++) {
tmpArray[i] = _currentStart - (i * 5);
}
_speedArray = tmpArray;
}
Component.onCompleted:
{
updateArray() ;
}
onAltitudeChanged: {
if(Math.abs(_currentCenter - altitude) > 50) {
updateArray() ;
}
}
anchors.verticalCenter: parent.verticalCenter
smooth: true
radius: ScreenTools.defaultFontPixelSize * (0.42)
border.color: Qt.rgba(1,1,1,0.25)
gradient: Gradient {
GradientStop { position: 0.0; color: Qt.rgba(0,0,0,0.65) }
GradientStop { position: 0.5; color: Qt.rgba(0,0,0,0.25) }
GradientStop { position: 1.0; color: Qt.rgba(0,0,0,0.65) }
}
Rectangle {
id: clipRect
height: parent.height - ScreenTools.defaultFontPixelSize * (0.42)
width: parent.width
clip: true
color: Qt.rgba(0,0,0,0);
anchors.verticalCenter: parent.verticalCenter
Column{
id: col
width: parent.width
anchors.verticalCenter: parent.verticalCenter
spacing: _reticleSpacing
Repeater {
model: _speedArray
anchors.left: parent.left
Rectangle {
property int _alt: modelData
width: (_alt % 10 === 0) ? ScreenTools.defaultFontPixelSize * (0.83) : ScreenTools.defaultFontPixelSize * (1.25)
height: _reticleHeight
color: Qt.rgba(1,1,1,0.35)
QGCLabel {
visible: (_alt % 10 === 0)
x: ScreenTools.defaultFontPixelSize * (1.66)
anchors.verticalCenter: parent.verticalCenter
antialiasing: true
font.weight: Font.DemiBold
text: _alt
color: _alt < 0 ? "#f8983a" : "white"
style: Text.Outline
styleColor: Qt.rgba(0,0,0,0.25)
}
}
}
transform: Translate {
y: ((altitude - _currentCenter) * _reticleSlot / 5) - (_reticleSlot / 2)
}
}
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief QGC Compass HUD
* @author Gus Grubba <mavlink@grubba.com>
*/
import QtQuick 2.4
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Item {
id: root
property bool active: false ///< true: actively connected to data provider, false: show inactive control
property real heading: _defaultHeading
readonly property real _defaultHeading: 0
property real _heading: active ? heading : _defaultHeading
Image {
id: compass
anchors.centerIn: parent
source: "/qmlimages/compass.svg"
mipmap: true
width: root.width
fillMode: Image.PreserveAspectFit
transform: Rotation {
origin.x: compass.width / 2
origin.y: compass.height / 2
angle: -_heading
}
}
Image {
id: pointer
anchors.bottom: compass.top
anchors.horizontalCenter: root.horizontalCenter
source: "/qmlimages/compassNeedle.svg"
smooth: true
width: compass.width * 0.1
fillMode: Image.PreserveAspectFit
}
Rectangle {
anchors.centerIn: compass
width: ScreenTools.defaultFontPixelSize * (3.33)
height: ScreenTools.defaultFontPixelSize * (2.08)
border.color: Qt.rgba(1,1,1,0.15)
color: Qt.rgba(0,0,0,0.25)
QGCLabel {
text: _heading.toFixed(0)
font.weight: Font.DemiBold
color: "white"
anchors.centerIn: parent
visible: active
}
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief QGC Current Altitude Indicator
* @author Gus Grubba <mavlink@grubba.com>
*/
import QtQuick 2.1
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Rectangle {
id: root
property bool active: false ///< true: actively connected to data provider, false: show inactive control
property real altitude: 0
property real vertZ: 0
property bool showAltitude: true
property bool showClimbRate: true
anchors.verticalCenter: parent.verticalCenter
width: parent.width
height: (showAltitude && showClimbRate) ? ScreenTools.defaultFontPixelSize * (4.16) : ScreenTools.defaultFontPixelSize * (2.08)
color: "black"
border.color: Qt.rgba(1,1,1,0.25)
opacity: 1.0
Column{
anchors.centerIn: parent
spacing: ScreenTools.defaultFontPixelSize * (0.33)
QGCLabel {
text: 'h: ' + (active ? altitude.toFixed(0) : "")
font.weight: Font.DemiBold
color: "white"
anchors.right: parent.right
visible: showAltitude
}
QGCLabel {
text: 'vZ: ' + (active ? vertZ.toFixed(0) : "")
color: "white"
font.weight: showAltitude ? Font.Normal : Font.DemiBold
anchors.right: parent.right
visible: showClimbRate
}
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief QGC Current Speed Indicator
* @author Gus Grubba <mavlink@grubba.com>
*/
import QtQuick 2.1
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Rectangle {
id: root
property bool active: false ///< true: actively connected to data provider, false: show inactive control
property real airspeed: 0
property real groundspeed: 0
property bool showAirSpeed: true
property bool showGroundSpeed: true
anchors.verticalCenter: parent.verticalCenter
width: parent.width
height: (showAirSpeed && showGroundSpeed) ? ScreenTools.defaultFontPixelSize * (4.16) : ScreenTools.defaultFontPixelSize * (2.08)
color: "black"
border.color: Qt.rgba(1,1,1,0.25)
opacity: 1.0
Column{
anchors.centerIn: parent
spacing: ScreenTools.defaultFontPixelSize * (0.33)
QGCLabel {
text: 'GS: ' + (active ? groundspeed.toFixed(0) : "")
font.weight: Font.DemiBold
color: "white"
anchors.right: parent.right
visible: showGroundSpeed
}
QGCLabel {
text: 'AS: ' + (active ? airspeed.toFixed(0) : "")
color: "white"
anchors.right: parent.right
font.weight: showAirSpeed ? Font.Normal : Font.DemiBold
visible: showAirSpeed
}
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief QGC Speed Indicator
* @author Gus Grubba <mavlink@grubba.com>
*/
import QtQuick 2.4
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
Rectangle {
id: root
property real speed: 0
property real _reticleSpacing: ScreenTools.defaultFontPixelSize * (0.83)
property real _reticleHeight: ScreenTools.defaultFontPixelSize * (0.166)
property real _reticleSlot: _reticleSpacing + _reticleHeight
anchors.verticalCenter: parent.verticalCenter
z:10
smooth: true
radius: ScreenTools.defaultFontPixelSize * (0.42)
border.color: Qt.rgba(1,1,1,0.25)
gradient: Gradient {
GradientStop { position: 0.0; color: Qt.rgba(0,0,0,0.65) }
GradientStop { position: 0.5; color: Qt.rgba(0,0,0,0.25) }
GradientStop { position: 1.0; color: Qt.rgba(0,0,0,0.65) }
}
Rectangle {
id: clipRect
height: parent.height - ScreenTools.defaultFontPixelSize * (0.42)
width: parent.width
clip: true
color: Qt.rgba(0,0,0,0);
anchors.verticalCenter: parent.verticalCenter
Column{
id: col
width: parent.width
anchors.verticalCenter: parent.verticalCenter
spacing: _reticleSpacing
Repeater {
model: 40
Rectangle {
property int _speed: -(index - 20)
width: (_speed % 5 === 0) ? ScreenTools.defaultFontPixelSize * (0.83) : ScreenTools.defaultFontPixelSize * (1.25)
anchors.right: parent.right
height: _reticleHeight
color: Qt.rgba(1,1,1,0.35)
QGCLabel {
visible: (_speed % 5 === 0)
anchors.horizontalCenter: parent.horizontalCenter
anchors.horizontalCenterOffset: ScreenTools.defaultFontPixelSize * (-2.5)
anchors.verticalCenter: parent.verticalCenter
antialiasing: true
font.weight: Font.DemiBold
text: _speed
color: _speed < 0 ? "#f8983a" : "white"
style: Text.Outline
styleColor: Qt.rgba(0,0,0,0.25)
}
}
}
transform: Translate {
y: (speed * _reticleSlot) - (_reticleSlot / 2)
}
}
}
}
......@@ -5,18 +5,13 @@ FlightMap 1.0 FlightMap.qml
QGCVideoBackground 1.0 QGCVideoBackground.qml
# Widgets
QGCAltitudeWidget 1.0 QGCAltitudeWidget.qml
QGCArtificialHorizon 1.0 QGCArtificialHorizon.qml
QGCAttitudeHUD 1.0 QGCAttitudeHUD.qml
QGCAttitudeWidget 1.0 QGCAttitudeWidget.qml
QGCCompassHUD 1.0 QGCCompassHUD.qml
QGCCompassWidget 1.0 QGCCompassWidget.qml
QGCCurrentAltitude 1.0 QGCCurrentAltitude.qml
QGCCurrentSpeed 1.0 QGCCurrentSpeed.qml
QGCInstrumentWidget 1.0 QGCInstrumentWidget.qml
QGCPitchIndicator 1.0 QGCPitchIndicator.qml
QGCSlider 1.0 QGCSlider.qml
QGCSpeedWidget 1.0 QGCSpeedWidget.qml
# Map items
MissionItemIndicator 1.0 MissionItemIndicator.qml
......
......@@ -38,7 +38,9 @@ import QGroundControl.Controllers 1.0
/// Mission Editor
QGCView {
viewPanel: panel
id: _root
viewPanel: panel
// zOrder comes from the Loader in MainWindow.qml
z: QGroundControl.zOrderTopMost
......@@ -89,6 +91,15 @@ QGCView {
}
}
function showDistance(missionItem) {
if (missionItem.distance < 0.0) {
waypointDistanceDisplay.visible = false
} else {
waypointDistanceDisplay.distance = missionItem.distance
waypointDistanceDisplay.visible = true
}
}
MissionController {
id: controller
......@@ -184,9 +195,9 @@ QGCView {
y: missionItemIndicator ? (missionItemIndicator.y + missionItemIndicator.anchorPoint.y - (itemDragger.height / 2)) : 100
width: _radius * 2
height: _radius * 2
radius: _radius
border.width: 2
border.color: "white"
//radius: _radius
//border.width: 2
//border.color: "white"
color: "transparent"
visible: false
z: QGroundControl.zOrderMapItems + 1 // Above item icons
......@@ -285,6 +296,7 @@ QGCView {
itemDragger.missionItem.coordinate = coordinate
editorMap.latitude = itemDragger.missionItem.coordinate.latitude
editorMap.longitude = itemDragger.missionItem.coordinate.longitude
_root.showDistance(itemDragger.missionItem)
}
}
}
......@@ -313,19 +325,22 @@ QGCView {
target: object
onIsCurrentItemChanged: {
if (object.isCurrentItem && object.specifiesCoordinate) {
// Setup our drag item
if (object.sequenceNumber != 0) {
itemDragger.visible = true
itemDragger.missionItem = Qt.binding(function() { return object })
itemDragger.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
itemDragger.clearItem()
}
if (object.isCurrentItem) {
_root.showDistance(object)
if (object.specifiesCoordinate) {
// Setup our drag item
if (object.sequenceNumber != 0) {
itemDragger.visible = true
itemDragger.missionItem = Qt.binding(function() { return object })
itemDragger.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
itemDragger.clearItem()
}
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
}
}
}
}
......@@ -854,6 +869,31 @@ QGCView {
z: QGroundControl.zOrderWidgets
checked: _showHelp
}
Rectangle {
id: waypointDistanceDisplay
anchors.margins: margins
anchors.left: parent.left
anchors.bottom: parent.bottom
width: distanceLabel.width + margins
height: distanceLabel.height + margins
radius: ScreenTools.defaultFontPixelWidth
color: qgcPal.window
opacity: 0.80
visible: false
property real distance: 0
readonly property real margins: ScreenTools.defaultFontPixelWidth
QGCLabel {
id: distanceLabel
anchors.verticalCenter: parent.verticalCenter
anchors.horizontalCenter: parent.horizonalCenter
color: qgcPal.text
text: "Distance: " + Math.round(parent.distance) + " meters"
}
}
} // FlightMap
} // Item - split view container
} // QGCViewPanel
......
......@@ -80,6 +80,7 @@ MissionItem::MissionItem(QObject* parent,
, _autocontinue(autocontinue)
, _isCurrentItem(isCurrentItem)
, _reachedTime(0)
, _distance(0.0)
, _headingDegreesFact(NULL)
, _dirty(false)
, _homePositionSpecialCase(false)
......@@ -189,6 +190,7 @@ const MissionItem& MissionItem::operator=(const MissionItem& other)
_command = other._command;
_autocontinue = other._autocontinue;
_reachedTime = other._reachedTime;
_distance = other._distance;
_altitudeRelativeToHomeFact = other._altitudeRelativeToHomeFact;
_dirty = other._dirty;
_homePositionSpecialCase = other._homePositionSpecialCase;
......@@ -231,7 +233,8 @@ void MissionItem::_connectSignals(void)
connect(_longitudeFact, &Fact::valueChanged, this, &MissionItem::_coordinateFactChanged);
connect(_altitudeFact, &Fact::valueChanged, this, &MissionItem::_coordinateFactChanged);
connect(_headingDegreesFact, &Fact::valueChanged, this, &MissionItem::_headingDegreesFactChanged);
connect(_headingDegreesFact, &Fact::valueChanged, this, &MissionItem::_headingDegreesFactChanged);
connect(_altitudeRelativeToHomeFact, &Fact::valueChanged, this, &MissionItem::_altitudeRelativeToHomeFactChanged);
}
MissionItem::~MissionItem()
......@@ -282,7 +285,6 @@ void MissionItem::setSequenceNumber(int sequenceNumber)
{
_sequenceNumber = sequenceNumber;
emit sequenceNumberChanged(_sequenceNumber);
emit changed(this);
}
void MissionItem::setX(double x)
......@@ -314,7 +316,6 @@ void MissionItem::setLatitude(double lat)
if (_latitudeFact->value().toDouble() != lat)
{
_latitudeFact->setValue(lat);
emit changed(this);
emit coordinateChanged(coordinate());
}
}
......@@ -324,7 +325,6 @@ void MissionItem::setLongitude(double lon)
if (_longitudeFact->value().toDouble() != lon)
{
_longitudeFact->setValue(lon);
emit changed(this);
emit coordinateChanged(coordinate());
}
}
......@@ -334,7 +334,6 @@ void MissionItem::setAltitude(double altitude)
if (_altitudeFact->value().toDouble() != altitude)
{
_altitudeFact->setValue(altitude);
emit changed(this);
emit valueStringsChanged(valueStrings());
emit coordinateChanged(coordinate());
}
......@@ -376,7 +375,6 @@ void MissionItem::setAction(int /*MAV_CMD*/ action)
setFrame(MAV_FRAME_MISSION);
}
emit changed(this);
emit commandNameChanged(commandName());
emit commandChanged((MavlinkQmlSingleton::Qml_MAV_CMD)_command);
emit valueLabelsChanged(valueLabels());
......@@ -398,7 +396,7 @@ void MissionItem::setFrame(int /*MAV_FRAME*/ frame)
if (_frame != frame) {
_altitudeRelativeToHomeFact->setValue(frame == MAV_FRAME_GLOBAL_RELATIVE_ALT);
_frame = frame;
emit changed(this);
emit frameChanged(_frame);
}
}
......@@ -406,7 +404,7 @@ void MissionItem::setAutocontinue(bool autoContinue)
{
if (_autocontinue != autoContinue) {
_autocontinue = autoContinue;
emit changed(this);
emit autoContinueChanged(_autocontinue);
}
}
......@@ -428,7 +426,6 @@ void MissionItem::setParam1(double param)
if (param1() != param)
{
_param1Fact->setValue(param);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
}
......@@ -439,7 +436,6 @@ void MissionItem::setParam2(double param)
{
_param2Fact->setValue(param);
emit valueStringsChanged(valueStrings());
emit changed(this);
}
}
......@@ -473,7 +469,6 @@ void MissionItem::setLoiterOrbitRadius(double radius)
if (loiterOrbitRadius() != radius) {
_loiterOrbitRadiusFact->setValue(radius);
emit valueStringsChanged(valueStrings());
emit changed(this);
}
}
......@@ -813,7 +808,6 @@ void MissionItem::setHeadingDegrees(double headingDegrees)
{
if (_headingDegreesFact->value().toDouble() != headingDegrees) {
_headingDegreesFact->setValue(headingDegrees);
emit changed(this);
emit valueStringsChanged(valueStrings());
emit headingDegreesChanged(headingDegrees);
}
......@@ -911,8 +905,25 @@ void MissionItem::_headingDegreesFactChanged(QVariant value)
emit headingDegreesChanged(value.toDouble());
}
void MissionItem::_altitudeRelativeToHomeFactChanged(QVariant value)
{
// Don't call setFrame, that will cause a signalling loop
int frame = value.toBool() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL;
if (_frame != frame) {
_frame = frame;
emit frameChanged(_frame);
}
}
void MissionItem::setHomePositionValid(bool homePositionValid)
{
_homePositionValid = homePositionValid;
emit homePositionValidChanged(_homePositionValid);
}
void MissionItem::setDistance(double distance)
{
_distance = distance;
emit distanceChanged(_distance);
}
......@@ -91,6 +91,9 @@ public:
/// true: home position should be shown
Q_PROPERTY(bool homePositionValid READ homePositionValid WRITE setHomePositionValid NOTIFY homePositionValidChanged)
/// Distance to previous waypoint, set by UI controller
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged)
// Property accesors
int sequenceNumber(void) const { return _sequenceNumber; }
......@@ -134,6 +137,9 @@ public:
bool homePosition(void) { return _homePositionSpecialCase; }
bool homePositionValid(void) { return _homePositionValid; }
void setHomePositionValid(bool homePositionValid);
double distance(void) { return _distance; }
void setDistance(double distance);
// C++ only methods
......@@ -207,6 +213,8 @@ public:
void setHomePositionSpecialCase(bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
bool relativeAltitude(void) { return _frame == MAV_FRAME_GLOBAL_RELATIVE_ALT; }
static const double defaultPitch;
static const double defaultHeading;
static const double defaultAltitude;
......@@ -221,15 +229,13 @@ signals:
void headingDegreesChanged(double heading);
void dirtyChanged(bool dirty);
void homePositionValidChanged(bool homePostionValid);
/** @brief Announces a change to the waypoint data */
void changed(MissionItem* wp);
void distanceChanged(float distance);
void frameChanged(int frame);
void commandNameChanged(QString type);
void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void valueLabelsChanged(QStringList valueLabels);
void valueStringsChanged(QStringList valueStrings);
bool autoContinueChanged(bool autoContinue);
public:
/** @brief Set the waypoint action */
......@@ -253,14 +259,11 @@ public:
/** @brief Wether this waypoint has been reached yet */
bool isReached () { return (_reachedTime > 0); }
void setChanged() {
emit changed(this);
}
private slots:
void _factValueChanged(QVariant value);
void _coordinateFactChanged(QVariant value);
void _headingDegreesFactChanged(QVariant value);
void _altitudeRelativeToHomeFactChanged(QVariant value);
private:
QString _oneDecimalString(double value);
......@@ -279,6 +282,7 @@ private:
bool _autocontinue;
bool _isCurrentItem;
quint64 _reachedTime;
double _distance;
Fact* _latitudeFact;
Fact* _longitudeFact;
......
......@@ -288,24 +288,72 @@ void MissionController::saveMissionToFile(void)
_missionItems->setDirty(false);
}
double MissionController::_calcDistance(bool homePositionValid, double homeAlt, MissionItem* item1, MissionItem* item2)
{
QGeoCoordinate coord1 = item1->coordinate();
QGeoCoordinate coord2 = item2->coordinate();
bool distanceOk = false;
// Convert to fixed altitudes
qCDebug(MissionControllerLog) << homePositionValid << homeAlt
<< item1->relativeAltitude() << item1->coordinate().altitude()
<< item2->relativeAltitude() << item2->coordinate().altitude();
if (homePositionValid) {
distanceOk = true;
if (item1->relativeAltitude()) {
coord1.setAltitude(homeAlt + coord1.altitude());
}
if (item2->relativeAltitude()) {
coord2.setAltitude(homeAlt + coord2.altitude());
}
} else {
if (item1->relativeAltitude() && item2->relativeAltitude()) {
distanceOk = true;
}
}
qCDebug(MissionControllerLog) << "distanceOk" << distanceOk;
if (distanceOk) {
return item1->coordinate().distanceTo(item2->coordinate());
} else {
return -1.0;
}
}
void MissionController::_recalcWaypointLines(void)
{
MissionItem* lastCoordinateItem = qobject_cast<MissionItem*>(_missionItems->get(0));
MissionItem* homeItem = lastCoordinateItem;
bool firstCoordinateItem = true;
bool homePositionValid = homeItem->homePositionValid();
double homeAlt = homeItem->coordinate().altitude();
qCDebug(MissionControllerLog) << "_recalcWaypointLines";
// If home position is valid we can calculate distances between all waypoints.
// If home position is not valid we can only calculate distances between waypoints which are
// both relative altitude.
// No distance for first item
lastCoordinateItem->setDistance(-1.0);
_waypointLines.clear();
for (int i=1; i<_missionItems->count(); i++) {
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
item->setDistance(-1.0); // Assume the worst
if (item->specifiesCoordinate()) {
if (firstCoordinateItem) {
if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
// The first coordinate we hit is a takeoff command so link back to home position if valid
if (homeItem->homePositionValid()) {
_waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate()));
if (homePositionValid) {
_waypointLines.append(new CoordinateVector(homeItem->coordinate(), item->coordinate()));
item->setDistance(_calcDistance(homePositionValid, homeAlt, homeItem, item));
}
} else {
// First coordiante is not a takeoff command, it does not link backwards to anything
......@@ -314,6 +362,7 @@ void MissionController::_recalcWaypointLines(void)
} else if (!lastCoordinateItem->homePosition() || lastCoordinateItem->homePositionValid()) {
// Subsequent coordinate items link to last coordinate item. If the last coordinate item
// is an invalid home position we skip the line
item->setDistance(_calcDistance(homePositionValid, homeAlt, lastCoordinateItem, item));
_waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
}
lastCoordinateItem = item;
......@@ -407,12 +456,14 @@ void MissionController::_initMissionItem(MissionItem* item)
connect(item, &MissionItem::commandChanged, this, &MissionController::_itemCommandChanged);
connect(item, &MissionItem::coordinateChanged, this, &MissionController::_itemCoordinateChanged);
connect(item, &MissionItem::frameChanged, this, &MissionController::_itemFrameChanged);
}
void MissionController::_deinitMissionItem(MissionItem* item)
{
disconnect(item, &MissionItem::commandChanged, this, &MissionController::_itemCommandChanged);
disconnect(item, &MissionItem::coordinateChanged, this, &MissionController::_itemCoordinateChanged);
disconnect(item, &MissionItem::frameChanged, this, &MissionController::_itemFrameChanged);
}
void MissionController::_itemCoordinateChanged(const QGeoCoordinate& coordinate)
......@@ -421,6 +472,12 @@ void MissionController::_itemCoordinateChanged(const QGeoCoordinate& coordinate)
_recalcWaypointLines();
}
void MissionController::_itemFrameChanged(int frame)
{
Q_UNUSED(frame);
_recalcWaypointLines();
}
void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
Q_UNUSED(command);;
......
......@@ -77,6 +77,7 @@ signals:
private slots:
void _newMissionItemsAvailableFromVehicle();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemFrameChanged(int frame);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
......@@ -96,6 +97,7 @@ private:
void _autoSyncSend(void);
void _setupMissionItems(bool loadFromVehicle, bool forceLoad);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
double _calcDistance(bool homePositionValid, double homeAlt, MissionItem* item1, MissionItem* item2);
private:
bool _editMode;
......
......@@ -12,7 +12,7 @@
// If you need to make an incompatible changes to stored settings, bump this version number
// up by 1. This will caused store settings to be cleared on next boot.
#define QGC_SETTINGS_VERSION 6
#define QGC_SETTINGS_VERSION 7
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_ORG_NAME "QGroundControl.org"
......
......@@ -187,13 +187,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
// Use the same shared pointer as LinkManager
_connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link));
#ifndef __mobile__
if (_connectedLinks.count() == 1) {
// This is the first link, we need to start logging
_startLogging();
}
#endif
// Send command to start MAVLink
// XXX hacky but safe
// Start NSH
......@@ -353,6 +346,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
#endif
if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
#ifndef __mobile__
// Start logging on first heartbeat
_startLogging();
#endif
// Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
......@@ -646,20 +644,20 @@ bool MAVLinkProtocol::_closeLogFile(void)
void MAVLinkProtocol::_startLogging(void)
{
Q_ASSERT(!_tempLogFile.isOpen());
if (!_tempLogFile.isOpen()) {
if (!_logSuspendReplay) {
if (!_tempLogFile.open()) {
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. "
"Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName()));
_closeLogFile();
_logSuspendError = true;
return;
}
qDebug() << "Temp log" << _tempLogFile.fileName();
if (!_logSuspendReplay) {
if (!_tempLogFile.open()) {
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. "
"Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName()));
_closeLogFile();
_logSuspendError = true;
return;
_logSuspendError = false;
}
qDebug() << "Temp log" << _tempLogFile.fileName();
_logSuspendError = false;
}
}
......
......@@ -63,7 +63,6 @@ This file is part of the QGROUNDCONTROL project
#include "UASRawStatusView.h"
#include "CustomCommandWidget.h"
#include "QGCDockWidget.h"
#include "FlightDisplayWidget.h"
#include "UASInfoWidget.h"
#include "HILDockWidget.h"
#endif
......@@ -89,7 +88,6 @@ const char* MainWindow::_mavlinkDockWidgetName = "MAVLink Inspector";
const char* MainWindow::_customCommandWidgetName = "Custom Command";
const char* MainWindow::_filesDockWidgetName = "Onboard Files";
const char* MainWindow::_uasStatusDetailsDockWidgetName = "Status Details";
const char* MainWindow::_pfdDockWidgetName = "Primary Flight Display";
const char* MainWindow::_uasInfoViewDockWidgetName = "Info View";
const char* MainWindow::_hilDockWidgetName = "HIL Config";
const char* MainWindow::_analyzeDockWidgetName = "Analyze";
......@@ -180,7 +178,7 @@ MainWindow::MainWindow()
_buildCommonWidgets();
emit initStatusChanged(tr("Building common actions"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141));
#endif
// Create actions
connectCommonActions();
// Connect user interface devices
......@@ -290,7 +288,7 @@ MainWindow::MainWindow()
qd.close();
#endif
}
#ifndef __mobile__
_loadVisibleWidgetsSettings();
#endif
......@@ -325,7 +323,6 @@ void MainWindow::_buildCommonWidgets(void)
_customCommandWidgetName,
_filesDockWidgetName,
_uasStatusDetailsDockWidgetName,
_pfdDockWidgetName,
_uasInfoViewDockWidgetName,
_hilDockWidgetName,
_analyzeDockWidgetName,
......@@ -334,14 +331,14 @@ void MainWindow::_buildCommonWidgets(void)
for (size_t i=0; i<cDockWidgetNames; i++) {
const char* pDockWidgetName = rgDockWidgetNames[i];
// Add to menu
QAction* action = new QAction(pDockWidgetName, NULL);
action->setCheckable(true);
action->setData(pDockWidgetName);
connect(action, &QAction::triggered, this, &MainWindow::_showDockWidgetAction);
_ui.menuWidgets->addAction(action);
_mapName2Action[pDockWidgetName] = action;
}
}
......@@ -353,13 +350,13 @@ void MainWindow::_showDockWidget(const QString& name, bool show)
if (!_mapName2DockWidget.contains(name)) {
_createInnerDockWidget(name);
}
Q_ASSERT(_mapName2DockWidget.contains(name));
QGCDockWidget* dockWidget = _mapName2DockWidget[name];
Q_ASSERT(dockWidget);
dockWidget->setVisible(show);
Q_ASSERT(_mapName2Action.contains(name));
_mapName2Action[name]->setChecked(show);
}
......@@ -368,7 +365,7 @@ void MainWindow::_showDockWidget(const QString& name, bool show)
void MainWindow::_createInnerDockWidget(const QString& widgetName)
{
QGCDockWidget* widget = NULL;
if (widgetName == _mavlinkDockWidgetName) {
widget = new QGCMAVLinkInspector(widgetName, _mapName2Action[widgetName], MAVLinkProtocol::instance(),this);
} else if (widgetName == _customCommandWidgetName) {
......@@ -377,8 +374,6 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName)
widget = new QGCUASFileViewMulti(widgetName, _mapName2Action[widgetName], this);
} else if (widgetName == _uasStatusDetailsDockWidgetName) {
widget = new UASInfoWidget(widgetName, _mapName2Action[widgetName], this);
} else if (widgetName == _pfdDockWidgetName) {
widget = new FlightDisplayWidget(widgetName, _mapName2Action[widgetName], this);
} else if (widgetName == _hilDockWidgetName) {
widget = new HILDockWidget(widgetName, _mapName2Action[widgetName], this);
} else if (widgetName == _analyzeDockWidgetName) {
......@@ -389,9 +384,9 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName)
widget = pInfoView;
} else {
qWarning() << "Attempt to create unknown Inner Dock Widget" << widgetName;
return;
return;
}
_mapName2DockWidget[widgetName] = widget;
}
......@@ -436,13 +431,13 @@ void MainWindow::closeEvent(QCloseEvent *event)
tr("There are still active connections to vehicles. Do you want to disconnect these before closing?"),
QMessageBox::Yes | QMessageBox::Cancel,
QMessageBox::Cancel);
if (button == QMessageBox::Yes) {
LinkManager::instance()->disconnectAll();
// The above disconnect causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
QTimer::singleShot(1500, this, &MainWindow::_closeWindow);
}
if (button == QMessageBox::Yes) {
LinkManager::instance()->disconnectAll();
// The above disconnect causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
QTimer::singleShot(1500, this, &MainWindow::_closeWindow);
}
event->ignore();
return;
......@@ -450,7 +445,7 @@ void MainWindow::closeEvent(QCloseEvent *event)
// This will process any remaining flight log save dialogs
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
// Should not be any active connections
Q_ASSERT(!LinkManager::instance()->anyConnectedLinks());
......@@ -486,7 +481,7 @@ void MainWindow::storeSettings()
settings.setValue("SHOW_STATUSBAR", _showStatusBar);
settings.endGroup();
settings.setValue(_getWindowGeometryKey(), saveGeometry());
#ifndef __mobile__
_storeVisibleWidgetsSettings();
#endif
......@@ -578,7 +573,7 @@ void MainWindow::_storeCurrentViewState(void)
dockWidget->saveSettings();
}
#endif
settings.setValue(_getWindowGeometryKey(), saveGeometry());
}
......@@ -638,12 +633,12 @@ void MainWindow::_showQmlTestWidget(void)
void MainWindow::_loadVisibleWidgetsSettings(void)
{
QSettings settings;
QString widgets = settings.value(_visibleWidgetsKey).toString();
if (!widgets.isEmpty()) {
QStringList nameList = widgets.split(",");
foreach (const QString &name, nameList) {
_showDockWidget(name, true);
}
......@@ -654,7 +649,7 @@ void MainWindow::_storeVisibleWidgetsSettings(void)
{
QString widgetNames;
bool firstWidget = true;
foreach (const QString &name, _mapName2DockWidget.keys()) {
if (_mapName2DockWidget[name]->isVisible()) {
if (!firstWidget) {
......@@ -662,13 +657,13 @@ void MainWindow::_storeVisibleWidgetsSettings(void)
} else {
firstWidget = false;
}
widgetNames += name;
}
}
QSettings settings;
settings.setValue(_visibleWidgetsKey, widgetNames);
}
#endif
......@@ -203,13 +203,13 @@ protected:
private slots:
void _linkStateChange(LinkInterface*);
void _closeWindow(void) { close(); }
void _closeWindow(void) { close(); }
void _vehicleAdded(Vehicle* vehicle);
#ifndef __mobile__
void _showDockWidgetAction(bool show);
#endif
#ifdef UNITTEST_BUILD
void _showQmlTestWidget(void);
#endif
......@@ -232,7 +232,6 @@ private:
static const char* _customCommandWidgetName;
static const char* _filesDockWidgetName;
static const char* _uasStatusDetailsDockWidgetName;
static const char* _pfdDockWidgetName;
static const char* _uasInfoViewDockWidgetName;
static const char* _hilDockWidgetName;
static const char* _analyzeDockWidgetName;
......@@ -251,7 +250,7 @@ private:
void _showDockWidget(const QString &name, bool show);
void _loadVisibleWidgetsSettings(void);
void _storeVisibleWidgetsSettings(void);
static const char* _visibleWidgetsKey;
#endif
......
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