Commit b4784c40 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into pairingTweaks

parents 12117523 402c24f5
......@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* Compass Instrument: Add indicators for Home, COG and Next Waypoint headings.
* Log Replay: Support changing speed of playback
* Basic object avoidance added to vehicles.
* Added ability to set a joystick button to be single action or repeated action while the button is held down.
......
......@@ -69,6 +69,8 @@
<file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file>
<file alias="compassInstrumentArrow.svg">src/FlightMap/Images/compassInstrumentArrow.svg</file>
<file alias="compassInstrumentDial.svg">src/FlightMap/Images/compassInstrumentDial.svg</file>
<file alias="compassDottedLine.svg">src/FlightMap/Images/compassDottedLine.svg</file>
<file alias="cOGPointer.svg">src/FlightMap/Images/cOGPointer.svg</file>
<file alias="Connect.svg">src/ui/toolbar/Images/Connect.svg</file>
<file alias="crossHair.svg">src/FlightMap/Images/crossHair.svg</file>
<file alias="DatalinkLoss.svg">src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg</file>
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include <QObject>
//-----------------------------------------------------------------------------
/**
* Contains the status of the Airspace authorization
*/
class AirspaceAuthorization : public QObject {
Q_OBJECT
public:
enum PermitStatus {
PermitUnknown = 0,
PermitPending,
PermitAccepted,
PermitRejected,
};
Q_ENUM(PermitStatus)
};
......@@ -575,6 +575,19 @@ const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle)
2.0, // minimum trigger interval
this); // parent
_cameraList.append(QVariant::fromValue(metaData));
metaData = new CameraMetaData(
tr("Sony DSC-RX0"),
13.2, // sensorWidth
8.8, // sensorHeight
4800, // imageWidth
3200, // imageHeight
7.7, // focalLength
true, // true: landscape orientation
false, // true: camera is fixed orientation
0, // minimum trigger interval
this); // parent
_cameraList.append(QVariant::fromValue(metaData));
metaData = new CameraMetaData(
//-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-qx1-body-kit/specifications
......
......@@ -494,7 +494,6 @@ Item {
anchors.topMargin: ScreenTools.toolbarHeight + _margins
anchors.rightMargin: _margins
anchors.right: parent.right
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelWidth
z: _mapAndVideo.z + 4
visible: QGroundControl.multiVehicleManager.vehicles.count > 1 && QGroundControl.corePlugin.options.enableMultiVehicleList
......@@ -519,6 +518,7 @@ Item {
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.bottom: parent.bottom
anchors.top: singleMultiSelector.visible? singleMultiSelector.bottom:undefined
useLightColors: isBackgroundDark
missionController: _missionController
visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
......@@ -581,9 +581,6 @@ Item {
z: _mapAndVideo.z + 4
maxHeight: (_flightVideo.visible ? _flightVideo.y : parent.height) - toolStrip.y
buttonVisible: [true, _useChecklist, _guidedController.showTakeoff || !_guidedController.showLand, _guidedController.showLand && !_guidedController.showTakeoff, true, _guidedController.showPause, !_guidedController.showPause ]
buttonEnabled: [true, _useChecklist && activeVehicle && !activeVehicle.armed, _guidedController.showTakeoff, _guidedController.showLand, _guidedController.showRTL, _guidedController.showPause, _anyActionAvailable ]
property bool _anyActionAvailable: _guidedController.showStartMission || _guidedController.showResumeMission || _guidedController.showChangeAlt || _guidedController.showLandAbort
property var _actionModel: [
{
......@@ -622,35 +619,49 @@ Item {
{
name: "Plan",
iconSource: "/qmlimages/Plan.svg",
buttonVisible: true,
buttonEnabled: true,
},
{
name: "Checklist",
iconSource: "/qmlimages/check.svg",
buttonVisible: _useChecklist,
buttonEnabled: _useChecklist && activeVehicle && !activeVehicle.armed,
},
{
name: _guidedController.takeoffTitle,
iconSource: "/res/takeoff.svg",
action: _guidedController.actionTakeoff
name: _guidedController.takeoffTitle,
iconSource: "/res/takeoff.svg",
buttonVisible: _guidedController.showTakeoff || !_guidedController.showLand,
buttonEnabled: _guidedController.showTakeoff,
action: _guidedController.actionTakeoff
},
{
name: _guidedController.landTitle,
iconSource: "/res/land.svg",
action: _guidedController.actionLand
name: _guidedController.landTitle,
iconSource: "/res/land.svg",
buttonVisible: _guidedController.showLand && !_guidedController.showTakeoff,
buttonEnabled: _guidedController.showLand,
action: _guidedController.actionLand
},
{
name: _guidedController.rtlTitle,
iconSource: "/res/rtl.svg",
action: _guidedController.actionRTL
name: _guidedController.rtlTitle,
iconSource: "/res/rtl.svg",
buttonVisible: true,
buttonEnabled: _guidedController.showRTL,
action: _guidedController.actionRTL
},
{
name: _guidedController.pauseTitle,
iconSource: "/res/pause-mission.svg",
action: _guidedController.actionPause
name: _guidedController.pauseTitle,
iconSource: "/res/pause-mission.svg",
buttonVisible: _guidedController.showPause,
buttonEnabled: _guidedController.showPause,
action: _guidedController.actionPause
},
{
name: qsTr("Action"),
iconSource: "/res/action.svg",
action: -1
name: qsTr("Action"),
iconSource: "/res/action.svg",
buttonVisible: !_guidedController.showPause,
buttonEnabled: _anyActionAvailable,
action: -1
}
]
......
......@@ -74,7 +74,7 @@ Rectangle {
QGCLabel {
id: actionMessage
text: modelData.text
text: modelData.text ? modelData.text : ""
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
Layout.minimumWidth: _width
......
......@@ -135,6 +135,7 @@ Item {
QGCCompassWidget {
size: _widgetHeight
usedByMultipleVehicleList: true
vehicle: _vehicle
}
......
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
version="1.1"
id="Layer_3"
x="0px"
y="0px"
viewBox="0 0 288 288"
enable-background="new 0 0 288 288"
xml:space="preserve"
inkscape:version="0.91 r13725"
sodipodi:docname="cOGPointer.svg"><metadata
id="metadata11"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
id="defs9" /><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1918"
inkscape:window-height="1059"
id="namedview7"
showgrid="false"
inkscape:zoom="0.81944444"
inkscape:cx="-575.96973"
inkscape:cy="364.74688"
inkscape:window-x="1920"
inkscape:window-y="19"
inkscape:window-maximized="1"
inkscape:current-layer="Layer_3" /><polygon
points="144,46.2 133.2,17.4 154.8,17.4 "
id="polygon3"
transform="matrix(-1,0,0,-1,288,54.034031)"
style="fill:#24d3ee;fill-opacity:1" /><rect
x="135"
y="270"
fill="none"
width="18"
height="18"
id="rect5" /></svg>
\ No newline at end of file
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Generator: Adobe Illustrator 19.1.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
version="1.1"
id="Layer_2"
x="0px"
y="0px"
viewBox="-161 253 288 288"
enable-background="new -161 253 288 288"
xml:space="preserve"
inkscape:version="0.91 r13725"
sodipodi:docname="compassDottedLine.svg"><metadata
id="metadata131"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /></cc:Work></rdf:RDF></metadata><defs
id="defs129" /><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="958"
inkscape:window-height="1059"
id="namedview127"
showgrid="false"
inkscape:zoom="4.5274476"
inkscape:cx="124.86047"
inkscape:cy="273.06273"
inkscape:window-x="1920"
inkscape:window-y="19"
inkscape:window-maximized="0"
inkscape:current-layer="Layer_2"
inkscape:snap-bbox="true"
inkscape:snap-object-midpoints="true"
inkscape:snap-center="true" /><path
style="fill:#088006;fill-opacity:1;fill-rule:evenodd;stroke:#088006;stroke-width:7.11199999;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:3.29999995;stroke-dasharray:14.22399998,7.11199999;stroke-dashoffset:17.99335997;stroke-opacity:1"
d="m -17.131076,320.82151 0.10597,-60.58956"
id="path4263"
inkscape:connector-curvature="0" /></svg>
\ No newline at end of file
......@@ -36,8 +36,8 @@ MapQuickItem {
gimbalYaw: missionItem.missionGimbalYaw
vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
highlightSelected: true
onClicked: _item.clicked()
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
}
}
......@@ -33,19 +33,16 @@ MapItemView {
parent._retaskSequence = object.sequenceNumber
parent.flightWidgets.guidedModeBar.confirmAction(parent.flightWidgets.guidedModeBar.confirmRetask)
}
// These are the non-coordinate child mission items attached to this item
Row {
anchors.top: parent.top
anchors.left: parent.right
Repeater {
model: object.childItems
model: object.childItems
delegate: MissionItemIndexLabel {
label: object.abbreviation
checked: object.isCurrentItem
z: 2
label: object.abbreviation
checked: object.isCurrentItem
z: 2
}
}
}
......
......@@ -17,10 +17,11 @@
import QtQuick 2.3
import QtGraphicalEffects 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Palette 1.0
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Palette 1.0
Item {
id: root
......@@ -30,10 +31,40 @@ Item {
property real size: _defaultSize
property var vehicle: null
property real _defaultSize: ScreenTools.defaultFontPixelHeight * (10)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio
property real _heading: vehicle ? vehicle.heading.rawValue : 0
property real _defaultSize: ScreenTools.defaultFontPixelHeight * (10)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio
property real _heading: vehicle ? vehicle.heading.rawValue : 0
property real _headingToHome: vehicle ? vehicle.headingToHome.rawValue : 0
property real _groundSpeed: vehicle ? vehicle.groundSpeed.rawValue : 0
property real _headingToNextWP: vehicle ? vehicle.headingToNextWP.rawValue : 0
property real _courseOverGround:activeVehicle ? activeVehicle.gps.courseOverGround.rawValue : 0
property bool usedByMultipleVehicleList: false
function isCOGAngleOK(){
if(_groundSpeed < 0.5){
return false
}
else{
return vehicle && _showAdditionalIndicatorsCompass
}
}
function isHeadingHomeOK(){
return vehicle && _showAdditionalIndicatorsCompass && !isNaN(_headingToHome)
}
function isHeadingToNextWPOK(){
return vehicle && _showAdditionalIndicatorsCompass && !isNaN(_headingToNextWP)
}
function isNoseUpLocked(){
return _lockNoseUpCompass
}
readonly property bool _showAdditionalIndicatorsCompass: QGroundControl.settingsManager.flyViewSettings.showAdditionalIndicatorsCompass.value && !usedByMultipleVehicleList
readonly property bool _lockNoseUpCompass: QGroundControl.settingsManager.flyViewSettings.lockNoseUpCompass.value
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -51,6 +82,55 @@ Item {
anchors.fill: parent
visible: false
Image {
id: cOGPointer
source: isCOGAngleOK() ? "/qmlimages/cOGPointer.svg" : ""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.fill: parent
sourceSize.height: parent.height
transform: Rotation {
property var _angle:isNoseUpLocked()?_courseOverGround-_heading:_courseOverGround
origin.x: cOGPointer.width / 2
origin.y: cOGPointer.height / 2
angle: _angle
}
}
Image {
id: nextWPPointer
source: isHeadingToNextWPOK() ? "/qmlimages/compassDottedLine.svg":""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.fill: parent
sourceSize.height: parent.height
transform: Rotation {
property var _angle: isNoseUpLocked()?_headingToNextWP-_heading:_headingToNextWP
origin.x: cOGPointer.width / 2
origin.y: cOGPointer.height / 2
angle: _angle
}
}
Image {
id: homePointer
width: size * 0.1
source: isHeadingHomeOK() ? "/qmlimages/Home.svg" : ""
mipmap: true
fillMode: Image.PreserveAspectFit
anchors.centerIn: parent
sourceSize.width: width
transform: Translate {
property double _angle: isNoseUpLocked()?-_heading+_headingToHome:_headingToHome
x: size/2.3 * Math.sin((_angle)*(3.14/180))
y: - size/2.3 * Math.cos((_angle)*(3.14/180))
}
}
Image {
id: pointer
width: size * 0.65
......@@ -62,10 +142,11 @@ Item {
transform: Rotation {
origin.x: pointer.width / 2
origin.y: pointer.height / 2
angle: _heading
angle: isNoseUpLocked()?0:_heading
}
}
QGCColoredImage {
id: compassDial
source: "/qmlimages/compassInstrumentDial.svg"
......@@ -74,8 +155,14 @@ Item {
anchors.fill: parent
sourceSize.height: parent.height
color: qgcPal.text
transform: Rotation {
origin.x: compassDial.width / 2
origin.y: compassDial.height / 2
angle: isNoseUpLocked()?-_heading:0
}
}
Rectangle {
anchors.centerIn: parent
width: size * 0.35
......
......@@ -19,7 +19,7 @@ import QGroundControl.Palette 1.0
Rectangle {
id: root
width: getPreferredInstrumentWidth() * 0.7
width: getPreferredInstrumentWidth()
height: _outerRadius * 4 + _valuesWidget.height
radius: _outerRadius
color: qgcPal.window
......
......@@ -42,21 +42,27 @@ MicrohardHandler::close()
}
//-----------------------------------------------------------------------------
bool
void
MicrohardHandler::_start(uint16_t port, QHostAddress addr)
{
close();
_tcpSocket = new QTcpSocket();
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &MicrohardHandler::_readBytes);
qCDebug(MicrohardLog) << "Connecting to" << addr;
_tcpSocket->connectToHost(addr, port);
//-- TODO: This has to be removed. It's blocking the main thread.
if (!_tcpSocket->waitForConnected(1000)) {
QTimer::singleShot(1000, this, &MicrohardHandler::_testConnection);
}
//-----------------------------------------------------------------------------
void
MicrohardHandler::_testConnection()
{
if(_tcpSocket) {
if(_tcpSocket->state() == QAbstractSocket::ConnectedState) {
qCDebug(MicrohardLog) << "Connected";
return;
}
emit connected(0);
close();
return false;
}
return true;
}
......@@ -29,10 +29,11 @@ public:
virtual bool close ();
protected:
virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
virtual void _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
protected slots:
virtual void _readBytes () = 0;
virtual void _testConnection ();
signals:
void connected (int status);
......
......@@ -205,7 +205,13 @@ MicrohardManager::_setEnabled()
void
MicrohardManager::_connectedLoc(int status)
{
qCDebug(MicrohardLog) << "GND Microhard Settings Connected";
static const char* msg = "GND Microhard Settings: ";
if(status > 0)
qCDebug(MicrohardLog) << msg << "Connected";
else if(status < 0)
qCDebug(MicrohardLog) << msg << "Error";
else
qCDebug(MicrohardLog) << msg << "Not Connected";
_connectedStatus = status;
_locTimer.start(LONG_TIMEOUT);
emit connectedChanged();
......@@ -215,7 +221,13 @@ MicrohardManager::_connectedLoc(int status)
void
MicrohardManager::_connectedRem(int status)
{
qCDebug(MicrohardLog) << "AIR Microhard Settings Connected";
static const char* msg = "AIR Microhard Settings: ";
if(status > 0)
qCDebug(MicrohardLog) << msg << "Connected";
else if(status < 0)
qCDebug(MicrohardLog) << msg << "Error";
else
qCDebug(MicrohardLog) << msg << "Not Connected";
_linkConnectedStatus = status;
_remTimer.start(LONG_TIMEOUT);
emit linkConnectedChanged();
......
......@@ -27,7 +27,8 @@ MicrohardSettings::start()
{
qCDebug(MicrohardLog) << "Start Microhard Settings";
_loggedIn = false;
return _start(MICROHARD_SETTINGS_PORT, QHostAddress(_address));
_start(MICROHARD_SETTINGS_PORT, QHostAddress(_address));
return true;
}
//-----------------------------------------------------------------------------
......
......@@ -46,7 +46,7 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
mavlink_message_t messageOut;
mavlink_mission_item_t missionItem;
memset(&missionItem, 8, sizeof(missionItem));
memset(&missionItem, 0, sizeof(missionItem));
missionItem.target_system = _vehicle->id();
missionItem.target_component = _vehicle->defaultComponentId();
missionItem.seq = 0;
......
......@@ -33,8 +33,8 @@ public:
Q_PROPERTY(QString editorQml READ editorQml CONSTANT)
Q_PROPERTY(QObject* currentRallyPoint READ currentRallyPoint WRITE setCurrentRallyPoint NOTIFY currentRallyPointChanged)
Q_INVOKABLE void addPoint(QGeoCoordinate point);
Q_INVOKABLE void removePoint(QObject* rallyPoint);
Q_INVOKABLE void addPoint (QGeoCoordinate point);
Q_INVOKABLE void removePoint (QObject* rallyPoint);
bool supported (void) const final;
void save (QJsonObject& json) final;
......
This diff is collapsed.
......@@ -36,7 +36,7 @@ QGCFlickable {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: editorLabel.bottom
height: helpLabel.height + helpLabel.height + (_margin * 2)
height: infoLabel.height + (_margin * 2)
color: qgcPal.windowShadeDark
radius: _radius
......@@ -51,6 +51,7 @@ QGCFlickable {
text: qsTr("Rally Points provide alternate landing points when performing a Return to Launch (RTL).")
}
/*
QGCLabel {
id: helpLabel
anchors.margins: _margin
......@@ -62,6 +63,7 @@ QGCFlickable {
qsTr("Click in the map to add new rally points.") :
qsTr("This vehicle does not support Rally Points.")
}
*/
}
}
}
......@@ -14,11 +14,13 @@ Rectangle {
color: _currentItem ? qgcPal.missionItemEditor : qgcPal.windowShade
radius: _radius
signal clicked()
property var rallyPoint ///< RallyPoint object associated with editor
property var controller ///< RallyPointController
property bool _currentItem: rallyPoint ? rallyPoint === controller.currentRallyPoint : false
property color _outerTextColor: _currentItem ? "black" : qgcPal.text
property color _outerTextColor: qgcPal.text // _currentItem ? "black" : qgcPal.text
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
readonly property real _radius: ScreenTools.defaultFontPixelWidth / 2
......@@ -101,7 +103,6 @@ Rectangle {
Repeater {
model: rallyPoint ? rallyPoint.textFieldFacts : 0
QGCLabel {
text: modelData.name + ":"
}
......@@ -109,7 +110,6 @@ Rectangle {
Repeater {
model: rallyPoint ? rallyPoint.textFieldFacts : 0
FactTextField {
Layout.fillWidth: true
showUnits: true
......
......@@ -67,11 +67,11 @@ Item {
property var rallyPointObject
sourceItem: MissionItemIndexLabel {
id: itemIndexLabel
label: qsTr("R", "rally point map item label")
checked: _editingLayer == _layerRallyPoints ? rallyPointObject === myRallyPointController.currentRallyPoint : false
onClicked: myRallyPointController.currentRallyPoint = rallyPointObject
id: itemIndexLabel
label: qsTr("R", "rally point map item label")
checked: _editingLayer == _layerRallyPoints ? rallyPointObject === myRallyPointController.currentRallyPoint : false
highlightSelected: true
onClicked: myRallyPointController.currentRallyPoint = rallyPointObject
}
}
}
......
......@@ -108,25 +108,20 @@ Item {
z: QGroundControl.zOrderMapItems
missionItem: _missionItem
sequenceNumber: _missionItem.sequenceNumber
onClicked: _root.clicked(_missionItem.sequenceNumber)
onClicked: _root.clicked(_missionItem.sequenceNumber)
// These are the non-coordinate child mission items attached to this item
Row {
anchors.top: parent.top
anchors.left: parent.right
Repeater {
model: _missionItem.childItems
delegate: MissionItemIndexLabel {
z: 2
label: object.abbreviation.length === 0 ? object.sequenceNumber : object.abbreviation.charAt(0)
checked: object.isCurrentItem
child: true
specifiesCoordinate: false
onClicked: _root.clicked(object.sequenceNumber)
onClicked: _root.clicked(object.sequenceNumber)
}
}
}
......
......@@ -56,7 +56,7 @@ void QGCPalette::_buildMap()
DECLARE_QGC_COLOR(text, "#9d9d9d", "#000000", "#707070", "#ffffff")
DECLARE_QGC_COLOR(warningText, "#cc0808", "#cc0808", "#f85761", "#f85761")
DECLARE_QGC_COLOR(button, "#ffffff", "#ffffff", "#707070", "#626270")
DECLARE_QGC_COLOR(buttonText, "#9d9d9d", "#000000", "#202020", "#ffffff")
DECLARE_QGC_COLOR(buttonText, "#9d9d9d", "#000000", "#A6A6A6", "#ffffff")
DECLARE_QGC_COLOR(buttonHighlight, "#e4e4e4", "#946120", "#3a3a3a", "#fff291")
DECLARE_QGC_COLOR(buttonHighlightText, "#2c2c2c", "#ffffff", "#2c2c2c", "#000000")
DECLARE_QGC_COLOR(primaryButton, "#585858", "#8cb3be", "#585858", "#8cb3be")
......
......@@ -17,6 +17,7 @@ Canvas {
property bool checked: false
property bool small: false
property bool child: false
property bool highlightSelected: false
property var color: checked ? "green" : (child ? qgcPal.mapIndicatorChild : qgcPal.mapIndicator)
property real anchorPointX: _height / 2
property real anchorPointY: _height / 2
......@@ -114,6 +115,17 @@ Canvas {
}
}
Rectangle {
width: indicator.width * 2
height: width
radius: width * 0.5
color: Qt.rgba(0,0,0,0)
border.color: Qt.rgba(1,1,1,0.5)
border.width: 1
visible: checked && highlightSelected
anchors.centerIn: indicator
}
QGCMouseArea {
fillItem: parent
onClicked: {
......
......@@ -30,10 +30,8 @@ Button {
QGCPalette { id: qgcPalDisabled; colorGroupEnabled: false }
// Initial state
state: "Default"
state: "Default"
// Update state on status changed
onEnabledChanged: state = "Default"
// Content Icon + Text
contentItem: Item {
id: contentLayoutItem
......@@ -79,8 +77,8 @@ Button {
name: "Hovering"
PropertyChanges {
target: button;
_currentColor: (checked || pressed) ? qgcPal.buttonHighlight : qgcPal.hoverColor
_currentContentColor: qgcPal.buttonHighlightText
_currentColor: (checked || pressed) ? qgcPal.buttonHighlight : qgcPal.hoverColor
_currentContentColor: qgcPal.buttonHighlightText
}
PropertyChanges {
target: buttonBkRect
......@@ -91,8 +89,8 @@ Button {
name: "Default"
PropertyChanges {
target: button;
_currentColor: enabled ? ((checked || pressed) ? qgcPal.buttonHighlight : qgcPal.button) : qgcPalDisabled.button
_currentContentColor: enabled ? ((checked || pressed) ? qgcPal.buttonHighlightText : qgcPal.buttonText) : qgcPalDisabled.buttonText
_currentColor: enabled ? ((checked || pressed) ? qgcPal.buttonHighlight : qgcPal.button) : qgcPalDisabled.button
_currentContentColor: enabled ? ((checked || pressed) ? qgcPal.buttonHighlightText : qgcPal.buttonText) : qgcPalDisabled.buttonText
}
PropertyChanges {
target: buttonBkRect
......@@ -114,19 +112,19 @@ Button {
// Process hover events
MouseArea {
enabled: !ScreenTools.isMobile
hoverEnabled: true
enabled: !ScreenTools.isMobile
propagateComposedEvents: true
preventStealing: true
anchors.fill: button
onEntered: { button.state = 'Hovering'; }
onExited: { button.state = 'Default'; }
hoverEnabled: true
preventStealing: true
anchors.fill: button
onEntered: button.state = 'Hovering'
onExited: button.state = 'Default'
// Propagate events down
onClicked: { mouse.accepted = false; }
onDoubleClicked: { mouse.accepted = false; }
onPositionChanged: { mouse.accepted = false; }
onPressAndHold: { mouse.accepted = false; }
onPressed: { mouse.accepted = false }
onReleased: { mouse.accepted = false }
onClicked: { mouse.accepted = false; }
onDoubleClicked: { mouse.accepted = false; }
onPositionChanged: { mouse.accepted = false; }
onPressAndHold: { mouse.accepted = false; }
onPressed: { mouse.accepted = false }
onReleased: { mouse.accepted = false }
}
}
......@@ -9,12 +9,13 @@ import QGroundControl.ScreenTools 1.0
TabButton {
id: control
property bool _showHighlight: (pressed | hovered | checked)
QGCPalette { id: qgcPalDisabled; colorGroupEnabled: false }
background: Rectangle {
color: _showHighlight ? qgcPal.buttonHighlight : qgcPal.button
color: enabled ? (_showHighlight ? qgcPal.buttonHighlight : qgcPal.button) : qgcPalDisabled.button
}
contentItem: QGCLabel {
text: control.text
color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
color: enabled ? (_showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText) : qgcPalDisabled.buttonText
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
elide: Text.ElideRight
......
......@@ -23,12 +23,7 @@ Rectangle {
radius: ScreenTools.defaultFontPixelWidth / 2
property alias model: repeater.model
property var rotateImage ///< List of bool values, one for each button in strip - true: animation rotation, false: static image
property var animateImage ///< List of bool values, one for each button in strip - true: animate image, false: static image
property var buttonEnabled ///< List of bool values, one for each button in strip - true: button enabled, false: button disabled
property var buttonVisible ///< List of bool values, one for each button in strip - true: button visible, false: button invisible
property real maxHeight ///< Maximum height for control, determines whether text is hidden to make control shorter
property var showAlternateIcon ///< List of bool values, one for each button in strip - true: show alternate icon, false: show normal icon
property AbstractButton lastClickedButton: null
......@@ -37,9 +32,17 @@ Rectangle {
signal clicked(int index, bool checked)
function setChecked(idx, check) {
repeater.itemAt(idx).checked = check
}
function getChecked(idx) {
return repeater.itemAt(idx).checked
}
ButtonGroup {
id: buttonGroup
exclusive: false
id: buttonGroup
buttons: toolStripColumn.children
}
Column {
......@@ -54,21 +57,20 @@ Rectangle {
id: repeater
QGCHoverButton {
id: buttonTemplate
id: buttonTemplate
anchors.left: toolStripColumn.left
anchors.right: toolStripColumn.right
height: width
radius: ScreenTools.defaultFontPixelWidth / 2
fontPointSize: ScreenTools.smallFontPointSize
autoExclusive: true
enabled: _root.buttonEnabled ? _root.buttonEnabled[index] : true
visible: _root.buttonVisible ? _root.buttonVisible[index] : true
imageSource: (_root.showAlternateIcon && _root.showAlternateIcon[index]) ? _alternateIconSource : _iconSource
enabled: modelData.buttonEnabled
visible: modelData.buttonVisible
imageSource: modelData.showAlternateIcon ? modelData.alternateIconSource : modelData.iconSource
text: modelData.name
property var _iconSource: modelData.iconSource
property var _alternateIconSource: modelData.alternateIconSource
checked: modelData.checked !== undefined ? modelData.checked : checked
ButtonGroup.group: buttonGroup
// Only drop pannel and toggleable are checkable
......@@ -76,23 +78,14 @@ Rectangle {
onClicked: {
dropPanel.hide() // DropPanel will call hide on "lastClickedButton"
// Uncheck other checked buttons
// TODO: Implement ButtonGroup exclusive with checkable and uncheckable and get rid of this workaround
for(var i = 0; i < buttonGroup.buttons.length; i++) {
var b = buttonGroup.buttons[i]
if(b !== buttonTemplate) {
b.checked = false;
}
}
if (modelData.dropPanelComponent === undefined) {
_root.clicked(index, checked)
} else if (checked) {
var panelEdgeTopPoint = mapToItem(_root, width, 0)
dropPanel.show(panelEdgeTopPoint, height, modelData.dropPanelComponent)
}
lastClickedButton = buttonTemplate
if(_root && buttonTemplate)
_root.lastClickedButton = buttonTemplate
}
}
}
......
......@@ -25,6 +25,18 @@
"type": "bool",
"defaultValue": false
},
{
"name": "showAdditionalIndicatorsCompass",
"shortDescription": "Show additional heading indicators on Compass",
"type": "bool",
"defaultValue": false
},
{
"name": "lockNoseUpCompass",
"shortDescription": "Lock Compass Nose-Up",
"type": "bool",
"defaultValue": false
},
{
"name": "maxGoToLocationDistance",
"shortDescription": "Maximum distance allowed for Go To Location.",
......
......@@ -21,4 +21,6 @@ DECLARE_SETTINGSFACT(FlyViewSettings, guidedMinimumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, guidedMaximumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, showLogReplayStatusBar)
DECLARE_SETTINGSFACT(FlyViewSettings, alternateInstrumentPanel)
DECLARE_SETTINGSFACT(FlyViewSettings, showAdditionalIndicatorsCompass)
DECLARE_SETTINGSFACT(FlyViewSettings, lockNoseUpCompass)
DECLARE_SETTINGSFACT(FlyViewSettings, maxGoToLocationDistance)
......@@ -23,5 +23,7 @@ public:
DEFINE_SETTINGFACT(guidedMaximumAltitude)
DEFINE_SETTINGFACT(showLogReplayStatusBar)
DEFINE_SETTINGFACT(alternateInstrumentPanel)
DEFINE_SETTINGFACT(showAdditionalIndicatorsCompass)
DEFINE_SETTINGFACT(lockNoseUpCompass)
DEFINE_SETTINGFACT(maxGoToLocationDistance)
};
......@@ -73,6 +73,7 @@ const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_flightDistanceFactName = "flightDistance";
const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_headingToNextWPFactName = "headingToNextWP";
const char* Vehicle::_headingToHomeFactName = "headingToHome";
const char* Vehicle::_distanceToGCSFactName = "distanceToGCS";
const char* Vehicle::_hobbsFactName = "hobbs";
......@@ -203,6 +204,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
......@@ -404,6 +406,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
......@@ -438,6 +441,7 @@ void Vehicle::_commonInit(void)
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);
_missionManager = new MissionManager(this);
......@@ -447,6 +451,7 @@ void Vehicle::_commonInit(void)
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearTrajectoryPoints);
connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateHeadingToNextWP);
_parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
......@@ -481,6 +486,7 @@ void Vehicle::_commonInit(void)
_addFact(&_flightDistanceFact, _flightDistanceFactName);
_addFact(&_flightTimeFact, _flightTimeFactName);
_addFact(&_distanceToHomeFact, _distanceToHomeFactName);
_addFact(&_headingToNextWPFact, _headingToNextWPFactName);
_addFact(&_headingToHomeFact, _headingToHomeFactName);
_addFact(&_distanceToGCSFact, _distanceToGCSFactName);
_addFact(&_throttlePctFact, _throttlePctFactName);
......@@ -3795,6 +3801,23 @@ void Vehicle::_updateDistanceHeadingToHome(void)
}
}
void Vehicle::_updateHeadingToNextWP(void)
{
const int _currentIndex = _missionManager->currentIndex();
MissionItem _currentItem;
QList<MissionItem*> llist = _missionManager->missionItems();
if(llist.size()>_currentIndex && _currentIndex!=-1
&& llist[_currentIndex]->coordinate().longitude()!=0.0
&& coordinate().distanceTo(llist[_currentIndex]->coordinate())>5.0 ){
_headingToNextWPFact.setRawValue(coordinate().azimuthTo(llist[_currentIndex]->coordinate()));
}
else{
_headingToNextWPFact.setRawValue(qQNaN());
}
}
void Vehicle::_updateDistanceToGCS(void)
{
QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
......
......@@ -671,6 +671,7 @@ public:
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT)
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* headingToNextWP READ headingToNextWP CONSTANT)
Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT)
Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
......@@ -973,6 +974,7 @@ public:
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
Fact* flightDistance (void) { return &_flightDistanceFact; }
Fact* distanceToHome (void) { return &_distanceToHomeFact; }
Fact* headingToNextWP (void) { return &_headingToNextWPFact; }
Fact* headingToHome (void) { return &_headingToHomeFact; }
Fact* distanceToGCS (void) { return &_distanceToGCSFact; }
Fact* hobbs (void) { return &_hobbsFact; }
......@@ -1246,6 +1248,7 @@ private slots:
void _clearTrajectoryPoints(void);
void _clearCameraTriggerPoints(void);
void _updateDistanceHeadingToHome(void);
void _updateHeadingToNextWP(void);
void _updateDistanceToGCS(void);
void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready);
......@@ -1540,6 +1543,7 @@ private:
Fact _flightDistanceFact;
Fact _flightTimeFact;
Fact _distanceToHomeFact;
Fact _headingToNextWPFact;
Fact _headingToHomeFact;
Fact _distanceToGCSFact;
Fact _hobbsFact;
......@@ -1570,6 +1574,7 @@ private:
static const char* _flightDistanceFactName;
static const char* _flightTimeFactName;
static const char* _distanceToHomeFactName;
static const char* _headingToNextWPFactName;
static const char* _headingToHomeFactName;
static const char* _distanceToGCSFactName;
static const char* _hobbsFactName;
......
......@@ -104,6 +104,13 @@
"decimalPlaces": 1,
"units": "m"
},
{
"name": "headingToNextWP",
"shortDescription": "Next WP Heading",
"type": "double",
"decimalPlaces": 0,
"units": "deg"
},
{
"name": "flightTime",
"shortDescription": "Flight Time",
......
#pragma once
#ifdef Q_OS_WIN
#define CALLTYPEXBEE __stdcall
#else // Q_OS_WIN
#define CALLTYPEXBEE
/****************************************************************************
*
* (c) 2009-2018 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.
*
****************************************************************************/
/**
* @file
* @brief Brief Description
*
* @author James Goppertr <james.goppert@gmail.edu>
*
*/
#pragma once
#include <QIODevice>
#include <QtSerialPort/QSerialPort>
#include <iostream>
/**
* @brief The SerialInterface abstracts low level serial calls
*/
class SerialInterface : public QObject
{
Q_OBJECT
signals:
void aboutToClose();
public:
enum baudRateType
{
BAUD50, //POSIX ONLY
BAUD75, //POSIX ONLY
BAUD110,
BAUD134, //POSIX ONLY
BAUD150, //POSIX ONLY
BAUD200, //POSIX ONLY
BAUD300,
BAUD600,
BAUD1200,
BAUD1800, //POSIX ONLY
BAUD2400,
BAUD4800,
BAUD9600,
BAUD14400, //WINDOWS ONLY
BAUD19200,
BAUD38400,
BAUD56000, //WINDOWS ONLY
BAUD57600,
BAUD76800, //POSIX ONLY
BAUD115200,
BAUD128000, // WINDOWS ONLY
BAUD230400, // WINDOWS ONLY
BAUD256000, // WINDOWS ONLY
BAUD460800, // WINDOWS ONLY
BAUD921600 // WINDOWS ONLY
};
enum dataBitsType
{
DATA_5,
DATA_6,
DATA_7,
DATA_8
};
enum parityType
{
PAR_NONE,
PAR_ODD,
PAR_EVEN,
PAR_MARK, //WINDOWS ONLY
PAR_SPACE
};
enum stopBitsType
{
STOP_1,
STOP_1_5, //WINDOWS ONLY
STOP_2
};
enum flowType
{
FLOW_OFF,
FLOW_HARDWARE,
FLOW_XONXOFF
};
/**
* structure to contain port settings
*/
struct portSettings
{
baudRateType BaudRate;
dataBitsType DataBits;
parityType Parity;
stopBitsType StopBits;
flowType FlowControl;
long timeout_Millisec;
};
virtual bool isOpen() = 0;
virtual bool isWritable() = 0;
virtual qint64 bytesAvailable() = 0;
virtual int write(const char * data, qint64 size) = 0;
virtual void read(char * data, qint64 numBytes) = 0;
virtual void flush() = 0;
virtual void close() = 0;
virtual void open(QIODevice::OpenModeFlag flag) = 0;
virtual void setBaudRate(baudRateType baudrate) = 0;
virtual void setParity(parityType parity) = 0;
virtual void setStopBits(stopBitsType stopBits) = 0;
virtual void setDataBits(dataBitsType dataBits) = 0;
virtual void setTimeout(qint64 timeout) = 0;
virtual void setFlow(flowType flow) = 0;
};
using namespace TNX;
class SerialQserial : public SerialInterface
{
Q_OBJECT
private:
QSerialPort * _port;
TNX::QPortSettings settings;
signals:
void aboutToClose();
public:
SerialQserial(QString porthandle, QIODevice::OpenModeFlag flag=QIODevice::ReadWrite)
: _port(NULL) {
QObject::connect(_port,SIGNAL(aboutToClose()),this,SIGNAL(aboutToClose()));
settings.setBaudRate(QPortSettings::BAUDR_57600);
settings.setStopBits(QPortSettings::STOP_1);
settings.setDataBits(QPortSettings::DB_8);
settings.setFlowControl(QPortSettings::FLOW_OFF);
settings.setParity(QPortSettings::PAR_NONE);
_port = new QSerialPort(porthandle,settings);
_port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead);
}
~SerialQserial() {
delete _port;
_port = NULL;
}
virtual bool isOpen() {
return _port->isOpen();
}
virtual bool isWritable() {
_port->isWritable();
}
virtual qint64 bytesAvailable() {
return _port->bytesAvailable();
}
virtual int write(const char * data, qint64 size) {
return _port->write(data,size);
}
virtual void read(char * data, qint64 numBytes) {
_port->read(data,numBytes);
}
virtual void flush() {
_port->flushInBuffer();
_port->flushOutBuffer();
}
virtual void close() {
_port->close();
}
virtual void open(QIODevice::OpenModeFlag flag) {
_port->open(flag);
//flush();
}
virtual void setBaudRate(SerialInterface::baudRateType baudrate) {
// TODO get the baudrate enum to map to one another
settings.setBaudRate(QPortSettings::BAUDR_57600);
}
virtual void setParity(SerialInterface::parityType parity) {
settings.setParity(QPortSettings::PAR_NONE);
}
virtual void setStopBits(SerialInterface::stopBitsType stopBits) {
// TODO map
settings.setStopBits(QPortSettings::STOP_1);
}
virtual void setDataBits(SerialInterface::dataBitsType dataBits) {
// TODO map
settings.setDataBits(QPortSettings::DB_8);
}
virtual void setTimeout(qint64 timeout) {
// TODO implement
//_port->setTimeout(timeout);
}
virtual void setFlow(SerialInterface::flowType flow) {
// TODO map
settings.setFlowControl(QPortSettings::FLOW_OFF);
}
};
// vim:ts=4:sw=4:tw=78:expandtab:
......@@ -482,6 +482,21 @@ Rectangle {
property Fact _alternateInstrumentPanel: QGroundControl.settingsManager.flyViewSettings.alternateInstrumentPanel
}
FactCheckBox {
text: qsTr("Show additional heading indicators on Compass")
visible: _showAdditionalIndicatorsCompass.visible
fact: _showAdditionalIndicatorsCompass
property Fact _showAdditionalIndicatorsCompass: QGroundControl.settingsManager.flyViewSettings.showAdditionalIndicatorsCompass
}
FactCheckBox {
text: qsTr("Lock Compass Nose-Up")
visible: _lockNoseUpCompass.visible
fact: _lockNoseUpCompass
property Fact _lockNoseUpCompass: QGroundControl.settingsManager.flyViewSettings.lockNoseUpCompass
}
GridLayout {
columns: 2
......
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