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