Commit 6b431672 authored by Gus Grubba's avatar Gus Grubba

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

* 'master' of https://github.com/mavlink/qgroundcontrol:
  Pile of bug fixes
  Permit firmware to send responses until stdout handle is drained
  Add mavlink console support
  Deprecation comments
  Fix plan view geofence display
  Fix mock link calls
  Mavlink submodule update
parents ce911c01 799780bd
Subproject commit b5aaac46c4819bab0f80d4d071ae9a8fec439676
Subproject commit fb411385d5f00300ab5d04c5adb08e7e17670d58
......@@ -56,6 +56,7 @@
<file alias="GeoFence.svg">src/AutoPilotPlugins/PX4/Images/GeoFence.svg</file>
<file alias="GeoFenceLight.svg">src/AutoPilotPlugins/PX4/Images/GeoFenceLight.svg</file>
<file alias="GeoTagIcon">src/AnalyzeView/GeoTagIcon.svg</file>
<file alias="MavlinkConsoleIcon">src/AnalyzeView/MavlinkConsoleIcon.svg</file>
<file alias="LandMode.svg">src/AutoPilotPlugins/PX4/Images/LandMode.svg</file>
<file alias="LandModeCopter.svg">src/AutoPilotPlugins/PX4/Images/LandModeCopter.svg</file>
<file alias="LightsComponentIcon.png">src/AutoPilotPlugins/APM/Images/LightsComponentIcon.png</file>
......
......@@ -555,6 +555,7 @@ HEADERS += \
!MobileBuild {
HEADERS += \
src/AnalyzeView/GeoTagController.h \
src/AnalyzeView/MavlinkConsoleController.h \
src/GPS/Drivers/src/gps_helper.h \
src/GPS/Drivers/src/ubx.h \
src/GPS/GPSManager.h \
......@@ -718,6 +719,7 @@ contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
!MobileBuild {
SOURCES += \
src/AnalyzeView/GeoTagController.cc \
src/AnalyzeView/MavlinkConsoleController.cc \
src/GPS/Drivers/src/gps_helper.cpp \
src/GPS/Drivers/src/ubx.cpp \
src/GPS/GPSManager.cc \
......
......@@ -28,6 +28,7 @@
<file alias="FlightModesComponentSummary.qml">src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml</file>
<file alias="GeneralSettings.qml">src/ui/preferences/GeneralSettings.qml</file>
<file alias="GeoTagPage.qml">src/AnalyzeView/GeoTagPage.qml</file>
<file alias="MavlinkConsolePage.qml">src/AnalyzeView/MavlinkConsolePage.qml</file>
<file alias="JoystickConfig.qml">src/VehicleSetup/JoystickConfig.qml</file>
<file alias="LinkSettings.qml">src/ui/preferences/LinkSettings.qml</file>
<file alias="LogDownloadPage.qml">src/AnalyzeView/LogDownloadPage.qml</file>
......@@ -66,7 +67,6 @@
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemMapVisual.qml">src/PlanView/MissionItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/MissionItemStatus.qml">src/PlanView/MissionItemStatus.qml</file>
<file alias="QGroundControl/Controls/MissionSettingsMapVisual.qml">src/PlanView/MissionSettingsMapVisual.qml</file>
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/MultiRotorMotorDisplay.qml">src/QmlControls/MultiRotorMotorDisplay.qml</file>
<file alias="QGroundControl/Controls/OfflineMapButton.qml">src/QmlControls/OfflineMapButton.qml</file>
......
......@@ -18,6 +18,7 @@ import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0
Rectangle {
......@@ -35,6 +36,10 @@ Rectangle {
readonly property real _verticalMargin: _defaultTextHeight / 2
readonly property real _buttonWidth: _defaultTextWidth * 18
MavlinkConsoleController {
id: conController
}
QGCFlickable {
id: buttonScroll
width: buttonColumn.width
......@@ -95,6 +100,11 @@ Rectangle {
buttonText: qsTr("GeoTag Images")
pageSource: "GeoTagPage.qml"
}
ListElement {
buttonImage: "/qmlimages/MavlinkConsoleIcon"
buttonText: qsTr("Mavlink Console")
pageSource: "MavlinkConsolePage.qml"
}
}
Component.onCompleted: itemAt(0).checked = true
......
/****************************************************************************
*
* (c) 2009-2017 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.
*
****************************************************************************/
#include "MavlinkConsoleController.h"
#include "QGCApplication.h"
#include "UAS.h"
MavlinkConsoleController::MavlinkConsoleController()
: _cursor_home_pos{-1},
_cursor{0},
_vehicle{nullptr}
{
auto *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MavlinkConsoleController::_setActiveVehicle);
_setActiveVehicle(manager->activeVehicle());
}
MavlinkConsoleController::~MavlinkConsoleController()
{
if (_vehicle) {
QByteArray msg("");
_sendSerialData(msg, true);
}
}
void
MavlinkConsoleController::sendCommand(QString command)
{
command.append("\n");
_sendSerialData(qPrintable(command));
_cursor_home_pos = -1;
_cursor = _console_text.length();
}
void
MavlinkConsoleController::_setActiveVehicle(Vehicle* vehicle)
{
for (auto &con : _uas_connections)
disconnect(con);
_uas_connections.clear();
_vehicle = vehicle;
if (_vehicle) {
_incoming_buffer.clear();
_console_text.clear();
emit cursorChanged(0);
emit textChanged(_console_text);
_uas_connections << connect(_vehicle, &Vehicle::mavlinkSerialControl, this, &MavlinkConsoleController::_receiveData);
}
}
void
MavlinkConsoleController::_receiveData(uint8_t device, uint8_t, uint16_t, uint32_t, QByteArray data)
{
if (device != SERIAL_CONTROL_DEV_SHELL)
return;
// Append incoming data and parse for ANSI codes
_incoming_buffer.append(data);
auto old_size = _console_text.size();
_processANSItext();
auto new_size = _console_text.size();
// Update QML and cursor
if (old_size > new_size) {
// Rewind back so we don't get a warning to stderr
emit cursorChanged(new_size);
}
emit textChanged(_console_text);
emit cursorChanged(new_size);
}
void
MavlinkConsoleController::_sendSerialData(QByteArray data, bool close)
{
Q_ASSERT(_vehicle);
if (!_vehicle)
return;
// Send maximum sized chunks until the complete buffer is transmitted
while(data.size()) {
QByteArray chunk{data.left(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN)};
uint8_t flags = SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
if (close) flags = 0;
auto protocol = qgcApp()->toolbox()->mavlinkProtocol();
auto priority_link = _vehicle->priorityLink();
mavlink_message_t msg;
mavlink_msg_serial_control_pack_chan(
protocol->getSystemId(),
protocol->getComponentId(),
priority_link->mavlinkChannel(),
&msg,
SERIAL_CONTROL_DEV_SHELL,
flags,
0,
0,
chunk.size(),
reinterpret_cast<uint8_t*>(chunk.data()));
_vehicle->sendMessageOnLink(priority_link, msg);
data.remove(0, chunk.size());
}
}
void
MavlinkConsoleController::_processANSItext()
{
int i; // Position into the parsed buffer
// Iterate over the incoming buffer to parse off known ANSI control codes
for (i = 0; i < _incoming_buffer.size(); i++) {
if (_incoming_buffer.at(i) == '\x1B') {
// For ANSI codes we expect at most 4 incoming chars
if (i < _incoming_buffer.size() - 3 && _incoming_buffer.at(i+1) == '[') {
// Parse ANSI code
switch(_incoming_buffer.at(i+2)) {
default:
continue;
case 'H':
if (_cursor_home_pos == -1) {
// Assign new home position if home is unset
_cursor_home_pos = _cursor;
} else {
// Rewind write cursor position to home
_cursor = _cursor_home_pos;
}
break;
case 'K':
// Erase the current line to the end
{
auto next_lf = _console_text.indexOf('\n', _cursor);
if (next_lf > 0)
_console_text.remove(_cursor, next_lf + 1 - _cursor);
}
break;
case '2':
// Erase everything and rewind to home
if (_incoming_buffer.at(i+3) == 'J' && _cursor_home_pos != -1) {
// Keep newlines so textedit doesn't scroll annoyingly
int newlines = _console_text.mid(_cursor_home_pos).count('\n');
_console_text.remove(_cursor_home_pos, _console_text.size());
_console_text.append(QByteArray(newlines, '\n'));
_cursor = _cursor_home_pos;
}
// Even if we didn't understand this ANSI code, remove the 4th char
_incoming_buffer.remove(i+3,1);
break;
}
// Remove the parsed ANSI code and decrement the bufferpos
_incoming_buffer.remove(i, 3);
i--;
} else {
// We can reasonably expect a control code was fragemented
// Stop parsing here and wait for it to come in
break;
}
}
}
// Insert the new data and increment the write cursor
_console_text.insert(_cursor, _incoming_buffer.left(i));
_cursor += i;
// Remove written data from the incoming buffer
_incoming_buffer.remove(0, i);
}
/****************************************************************************
*
* (c) 2009-2017 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 "QmlObjectListModel.h"
#include "Fact.h"
#include "FactMetaData.h"
#include <QObject>
#include <QString>
#include <QThread>
#include <QFileInfoList>
#include <QElapsedTimer>
#include <QDebug>
#include <QGeoCoordinate>
#include <QMetaObject>
// Fordward decls
class Vehicle;
/// Controller for MavlinkConsole.qml.
class MavlinkConsoleController : public QObject
{
Q_OBJECT
Q_PROPERTY(int cursor READ cursor NOTIFY cursorChanged)
Q_PROPERTY(QString text READ text NOTIFY textChanged)
public:
MavlinkConsoleController();
~MavlinkConsoleController();
int cursor() const { return _console_text.size(); }
QString text() const { return _console_text; }
public slots:
void sendCommand(QString command);
signals:
void cursorChanged(int);
void textChanged(QString text);
private slots:
void _setActiveVehicle (Vehicle* vehicle);
void _receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
private:
void _processANSItext();
void _sendSerialData(QByteArray, bool close = false);
int _cursor_home_pos;
int _cursor;
QByteArray _incoming_buffer;
QString _console_text;
Vehicle* _vehicle;
QList<QMetaObject::Connection> _uas_connections;
};
<?xml version="1.0" encoding="utf-8"?>
<svg
xmlns="http://www.w3.org/2000/svg"
width="512"
height="512"
id="caret"
version="1.1">
<g
id="layer1"
transform="translate(0,-540.36218)">
<g
style="fill:#ffffff;fill-opacity:1;stroke:none;"
id="text2985">
<path
d="m 191.125,654.48718 168.5,141.75 -168.5,142 -38.75,-39.5 123.75,-102 -123.75,-102.75 z"
style="fill:#ffffff;fill-opacity:1" />
</g>
</g>
</svg>
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
AnalyzePage {
id: mavlinkConsolePage
pageComponent: pageComponent
pageName: qsTr("Mavlink Console")
pageDescription: qsTr("Mavlink Console provides a connection to the vehicle's system shell.")
Component {
id: pageComponent
ColumnLayout {
id: consoleColumn
height: availableHeight
width: availableWidth
TextArea {
id: consoleEditor
Layout.fillHeight: true
anchors.left: parent.left
anchors.right: parent.right
font.family: ScreenTools.fixedFontFamily
font.pointSize: ScreenTools.defaultFontPointSize
readOnly: true
cursorPosition: conController.cursor
text: conController.text
}
QGCTextField {
id: command
anchors.left: parent.left
anchors.right: parent.right
placeholderText: "Enter Commands here..."
onAccepted: {
conController.sendCommand(text)
text = ""
}
}
}
} // Component
} // AnalyzePage
......@@ -9,6 +9,12 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,
"specifiesAltitudeOnly": true
},
{
"id": 84,
"comment": "MAV_CMD_NAV_VTOL_TAKEOFF",
......
......@@ -14,12 +14,6 @@
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "4"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,
"specifiesAltitudeOnly": true
},
{
"id": 82,
"comment": "MAV_CMD_NAV_SPLINE_WAYPOINT",
......
......@@ -30,11 +30,9 @@
"paramRemove": "1,4"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,
"specifiesAltitudeOnly": true,
"paramRemove": "1,2,3,4"
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1,2,3,4"
},
{
"id": 31,
......
......@@ -10,9 +10,9 @@
"paramRemove": "2,3,4"
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1"
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1"
}
]
}
......@@ -21,6 +21,11 @@
"comment": "MAV_CMD_NAV_LOITER_TIME",
"description": "Travel to a position and Loiter for an amount of time.",
"paramRemove": "3,4"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1"
}
]
}
......@@ -521,3 +521,7 @@ void FixedWingLandingComplexItem::_setDirty(void)
setDirty(true);
}
void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
{
_loiterAltitudeFact.setRawValue(newAltitude);
}
......@@ -76,6 +76,7 @@ public:
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
......
......@@ -1228,6 +1228,7 @@ void MissionController::_initAllVisualItems(void)
}
connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
......@@ -1241,12 +1242,16 @@ void MissionController::_initAllVisualItems(void)
emit visualItemsChanged();
emit containsItemsChanged(containsItems());
emit plannedHomePositionChanged(plannedHomePosition());
_visualItems->setDirty(false);
}
void MissionController::_deinitAllVisualItems(void)
{
disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
for (int i=0; i<_visualItems->count(); i++) {
_deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
}
......@@ -1583,3 +1588,22 @@ void MissionController::resumeMission(int resumeIndex)
}
_activeVehicle->missionManager()->generateResumeMission(resumeIndex);
}
QGeoCoordinate MissionController::plannedHomePosition(void) const
{
if (_settingsItem) {
return _settingsItem->coordinate();
} else {
return QGeoCoordinate();
}
}
void MissionController::applyDefaultMissionAltitude(void)
{
double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();
for (int i=1; i<_visualItems->count(); i++) {
VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
item->applyNewAltitude(defaultAltitude);
}
}
......@@ -62,6 +62,7 @@ public:
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(int resumeMissionItem READ resumeMissionItem NOTIFY resumeMissionItemChanged)
......@@ -92,6 +93,9 @@ public:
Q_INVOKABLE void resumeMission(int resumeIndex);
/// Updates the altitudes of the items in the current mission to the new default altitude
Q_INVOKABLE void applyDefaultMissionAltitude(void);
/// Loads the mission items from the specified file
/// @param[in] vehicle Vehicle we are loading items for
/// @param[in] filename File to load from
......@@ -123,6 +127,7 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const;
/// Returns the item index two which a mission should be resumed. -1 indicates resume mission not available.
int resumeMissionItem(void) const;
......@@ -154,6 +159,7 @@ signals:
void resumeMissionReady(void);
void batteryChangePointChanged(int batteryChangePoint);
void batteriesRequiredChanged(int batteriesRequired);
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition);
private slots:
void _newMissionItemsAvailableFromVehicle(bool removeAllRequested);
......
......@@ -146,7 +146,7 @@ double MissionSettingsItem::greatestDistanceTo(const QGeoCoordinate &other) cons
bool MissionSettingsItem::specifiesCoordinate(void) const
{
return false;
return true;
}
void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
......
......@@ -62,7 +62,7 @@ public:
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
QString mapVisualQML (void) const final { return QStringLiteral("MissionSettingsMapVisual.qml"); }
QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
// Overrides from VisualMissionItem
......@@ -80,6 +80,7 @@ public:
double specifiedFlightSpeed (void) final;
double specifiedGimbalYaw (void) final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); /* no action */ }
bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
......
......@@ -728,3 +728,21 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
_cameraSection->appendMissionItems(items, missionItemParent, seqNum);
}
void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
MAV_CMD command = (MAV_CMD)this->command();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) {
switch ((MAV_CMD)this->command()) {
case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_VTOL_LAND:
// Leave alone
break;
default:
_missionItem.setParam7(newAltitude);
break;
}
}
}
......@@ -99,6 +99,7 @@ public:
double specifiedGimbalYaw (void) final;
QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); }
......
......@@ -1108,3 +1108,8 @@ double SurveyMissionItem::_turnaroundDistance(void) const
{
return _turnaroundDistFact.rawValue().toDouble();
}
void SurveyMissionItem::applyNewAltitude(double newAltitude)
{
_gridAltitudeFact.setRawValue(newAltitude);
}
......@@ -126,6 +126,7 @@ public:
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
......
......@@ -138,6 +138,9 @@ public:
/// @param missionItemParent Parent object for newly created MissionItems
virtual void appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) = 0;
/// Adjust the altitude of the item if appropriate to the new altitude.
virtual void applyNewAltitude(double newAltitude) = 0;
double missionGimbalYaw (void) const { return _missionGimbalYaw; }
double missionVehicleYaw (void) const { return _missionVehicleYaw; }
bool showMissionGimbalYaw(void) const { return !qIsNaN(_missionGimbalYaw); }
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// Mission Settings map visuals
Item {
id: _root
property var map ///< Map control to place item in
signal clicked(int sequenceNumber)
property var _missionItem: object
property var _itemVisual
property var _dragArea
property bool _itemVisualShowing: false
property bool _dragAreaShowing: false
function hideItemVisuals() {
if (_itemVisualShowing) {
_itemVisual.destroy()
_itemVisualShowing = false
}
}
function showItemVisuals() {
if (!_itemVisualShowing) {
_itemVisual = indicatorComponent.createObject(map)
map.addMapItem(_itemVisual)
_itemVisualShowing = true
}
}
function hideDragArea() {