Commit 8ce30794 authored by Don Gagne's avatar Don Gagne

Merge pull request #1848 from DonLakeFlyer/MissionEditor

Mission editor (WIP)
parents 0a770c97 69f27141
......@@ -144,6 +144,7 @@ INCLUDEPATH += \
src/input \
src/Joystick \
src/lib/qmapcontrol \
src/MissionEditor \
src/QmlControls \
src/uas \
src/ui \
......@@ -244,6 +245,7 @@ HEADERS += \
src/Joystick/JoystickManager.h \
src/LogCompressor.h \
src/MG.h \
src/MissionEditor/MissionEditor.h \
src/QGC.h \
src/QGCApplication.h \
src/QGCComboBox.h \
......@@ -381,6 +383,7 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionEditor/MissionEditor.cc \
src/QGC.cc \
src/QGCApplication.cc \
src/QGCComboBox.cc \
......
......@@ -100,6 +100,7 @@
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemSummary.qml">src/QmlControls/MissionItemSummary.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/QmlControls/MissionItemEditor.qml</file>
<!-- Vehicle Setup -->
<file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file>
......@@ -128,6 +129,7 @@
<file alias="FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file>
<file alias="FlightDisplayWidget.qml">src/FlightDisplay/FlightDisplayWidget.qml</file>
<file alias="MapDisplay.qml">src/ui/mapdisplay/MapDisplay.qml</file>
<file alias="MissionEditor.qml">src/MissionEditor/MissionEditor.qml</file>
<!-- FlightMap module -->
<file alias="QGroundControl/FlightMap/qmldir">src/FlightMap/qmldir</file>
......@@ -150,7 +152,7 @@
<file alias="QGroundControl/FlightMap/QGCWaypointEditor.qml">src/FlightMap/Widgets/QGCWaypointEditor.qml</file>
<!-- FlightMap MapQuickItems -->
<file alias="QGroundControl/FlightMap/MissionMapItem.qml">src/FlightMap/MapItems/MissionMapItem.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>
</qresource>
......
......@@ -95,8 +95,10 @@ Item {
model: multiVehicleManager.activeVehicle ? multiVehicleManager.activeVehicle.missionItems : 0
delegate:
MissionMapItem {
missionItem: object
MissionItemIndicator {
label: object.sequenceNumber
isCurrentItem: object.isCurrentItem
coordinate: object.coordinate
}
}
......
......@@ -76,13 +76,13 @@ Map {
Menu {
id: mapTypeMenu
title: "Map Type..."
enabled: root.visible
enabled: _map.visible
ExclusiveGroup { id: currMapType }
function setCurrentMap(mapID) {
for (var i = 0; i < _map.supportedMapTypes.length; i++) {
if (mapID === _map.supportedMapTypes[i].name) {
_map.activeMapType = _map.supportedMapTypes[i]
multiVehicleManager.saveSetting(root.mapName + "/currentMapType", mapID);
multiVehicleManager.saveSetting(_map.mapName + "/currentMapType", mapID);
return;
}
}
......@@ -100,7 +100,7 @@ Map {
var mapID = ''
if (_map.supportedMapTypes.length > 0)
mapID = _map.activeMapType.name;
mapID = multiVehicleManager.loadSetting(root.mapName + "/currentMapType", mapID);
mapID = multiVehicleManager.loadSetting(_map.mapName + "/currentMapType", mapID);
for (var i = 0; i < _map.supportedMapTypes.length; i++) {
var name = _map.supportedMapTypes[i].name;
addMap(name, mapID === name);
......
......@@ -30,14 +30,14 @@ import QGroundControl.Vehicle 1.0
/// Marker for displaying a mission item on the map
MapQuickItem {
property var missionItem ///< Mission Item object
property alias label: _label.label
property alias isCurrentItem: _label.isCurrentItem
anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2
coordinate: missionItem.coordinate
sourceItem:
MissionItemIndexLabel {
missionItemIndex: missionItem.id
id: _label
}
}
......@@ -21,4 +21,4 @@ QGCWaypointEditor 1.0 QGCWaypointEditor.qml
# MapQuickItems
VehicleMapItem 1.0 VehicleMapItem.qml
MissionMapItem 1.0 MissionMapItem.qml
MissionItemIndicator 1.0 MissionItemIndicator.qml
/*=====================================================================
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 "MissionEditor.h"
#include "ScreenToolsController.h"
#include <QQmlContext>
#include <QQmlEngine>
#include <QSettings>
const char* MissionEditor::_settingsGroup = "MissionEditor";
MissionEditor::MissionEditor(QWidget *parent)
: QGCQmlWidgetHolder(parent)
{
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
// Get rid of layout default margins
QLayout* pl = layout();
if(pl) {
pl->setContentsMargins(0,0,0,0);
}
#ifndef __android__
setMinimumWidth( 31 * ScreenToolsController::defaultFontPixelSize_s());
setMinimumHeight(33 * ScreenToolsController::defaultFontPixelSize_s());
#endif
setContextPropertyObject("controller", this);
setSource(QUrl::fromUserInput("qrc:/qml/MissionEditor.qml"));
}
MissionEditor::~MissionEditor()
{
}
void MissionEditor::saveSetting(const QString &name, const QString& value)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(name, value);
}
QString MissionEditor::loadSetting(const QString &name, const QString& defaultValue)
{
QSettings settings;
settings.beginGroup(_settingsGroup);
return settings.value(name, defaultValue).toString();
}
void MissionEditor::addMissionItem(QGeoCoordinate coordinate)
{
MissionItem * newItem = new MissionItem(this, _missionItems.count(), coordinate);
if (_missionItems.count() == 0) {
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
}
qDebug() << "MissionItem" << newItem->coordinate();
_missionItems.append(newItem);
}
/*=====================================================================
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 MissionEditor_H
#define MissionEditor_H
#include "QGCQmlWidgetHolder.h"
#include "QmlObjectListModel.h"
class MissionEditor : public QGCQmlWidgetHolder
{
Q_OBJECT
public:
MissionEditor(QWidget* parent = NULL);
~MissionEditor();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT)
Q_INVOKABLE void addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void saveSetting (const QString &key, const QString& value);
Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue);
// Property accessors
QmlObjectListModel* missionItemsModel(void) { return &_missionItems; }
private:
QmlObjectListModel _missionItems;
static const char* _settingsGroup;
};
#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.Dialogs 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
/// Mission Editor
Item {
// For some reason we can't have FlightMap as the top level control. If you do that it doesn't draw.
// So we have an Item at the top to work around that.
readonly property real _defaultLatitude: 37.803784
readonly property real _defaultLongitude: -122.462276
readonly property int _decimalPlaces: 7
FlightMap {
id: editorMap
anchors.fill: parent
mapName: "MissionEditor"
latitude: _defaultLatitude
longitude: _defaultLongitude
QGCLabel { text: "WIP: Non functional"; font.pixelSize: ScreenTools.largeFontPixelSize }
MouseArea {
anchors.fill: parent
onClicked: {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = 0
controller.addMissionItem(coordinate)
}
}
// Add the mission items to the map
MapItemView {
model: controller.missionItems
delegate:
MissionItemIndicator {
label: object.sequenceNumber
isCurrentItem: object.isCurrentItem
coordinate: object.coordinate
Component.onCompleted: console.log("Indicator", object.coordinate)
}
}
// Mission item list
ListView {
id: missionItemSummaryList
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.top: parent.top
anchors.bottom: editorMap.mapWidgets.top
anchors.right: parent.right
width: ScreenTools.defaultFontPixelWidth * 30
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical
model: controller.missionItems
property real _maxItemHeight: 0
delegate:
MissionItemEditor {
missionItem: object
}
}
Column {
id: controlWidgets
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.right: parent.left
anchors.bottom: parent.top
spacing: ScreenTools.defaultFontPixelWidth / 2
QGCButton {
id: addMode
text: "+"
checkable: true
}
}
}
}
This diff is collapsed.
......@@ -39,76 +39,84 @@ class MissionItem : public QObject
Q_OBJECT
public:
MissionItem(
QObject *parent = 0,
quint16 id = 0,
double x = 0.0,
double y = 0.0,
double z = 0.0,
double param1 = 0.0,
double param2 = 0.0,
double param3 = 0.0,
double param4 = 0.0,
bool autocontinue = true,
bool current = false,
int frame = MAV_FRAME_GLOBAL,
int action = MAV_CMD_NAV_WAYPOINT,
const QString& description=QString(""));
MissionItem(QObject *parent = 0,
int sequenceNumber = 0,
QGeoCoordinate coordiante = QGeoCoordinate(),
double param1 = 0.0,
double param2 = 0.0,
double param3 = 0.0,
double param4 = 0.0,
bool autocontinue = true,
bool isCurrentItem = false,
int frame = MAV_FRAME_GLOBAL,
int action = MAV_CMD_NAV_WAYPOINT);
MissionItem(const MissionItem& other);
~MissionItem();
const MissionItem& operator=(const MissionItem& other);
Q_PROPERTY(bool hasCoordinate READ hasCoordinate NOTIFY hasCoordinateChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(double yaw READ yaw WRITE setYaw NOTIFY yawChanged)
Q_PROPERTY(QStringList commandNames READ commandNames CONSTANT)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged)
Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged)
Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
// Property accesors
int sequenceNumber(void) const { return _sequenceNumber; }
void setSequenceNumber(int sequenceNumber);
bool isCurrentItem(void) const { return _isCurrentItem; }
void setIsCurrentItem(bool isCurrentItem);
Q_PROPERTY(double longitude READ longitude NOTIFY longitudeChanged)
Q_PROPERTY(double latitude READ latitude NOTIFY latitudeChanged)
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged)
Q_PROPERTY(quint16 id READ id CONSTANT)
bool specifiesCoordinate(void) const;
Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged)
Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
QGeoCoordinate coordinate(void) const { return _coordinate; }
void setCoordinate(const QGeoCoordinate& coordinate);
QStringList commandNames(void);
QString commandName(void);
double latitude() { return _x; }
double longitude() { return _y; }
double altitude() { return _z; }
quint16 id() { return _id; }
int commandByIndex(void);
void setCommandByIndex(int index);
MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)getAction(); };
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
QStringList valueLabels(void);
QStringList valueStrings(void);
// C++ only methods
quint16 getId() const {
return _id;
}
double getX() const {
return _x;
}
double getY() const {
return _y;
}
double getZ() const {
return _z;
}
double getLatitude() const {
return _x;
}
double getLongitude() const {
return _y;
}
double getAltitude() const {
return _z;
}
double getYaw() const {
return _yaw;
}
double latitude(void) const { return _coordinate.latitude(); }
double longitude(void) const { return _coordinate.longitude(); }
double altitude(void) const { return _coordinate.altitude(); }
void setLatitude(double latitude);
void setLongitude(double longitude);
void setAltitude(double altitude);
double x(void) const { return latitude(); }
double y(void) const { return longitude(); }
double z(void) const { return altitude(); }
void setX(double x);
void setY(double y);
void setZ(double z);
double yaw(void) const { return _yaw; }
void setYaw(double yaw);
bool getAutoContinue() const {
return _autocontinue;
}
bool getCurrent() const {
return _current;
}
double getLoiterOrbit() const {
return _orbit;
}
......@@ -128,16 +136,16 @@ public:
return _orbit;
}
double getParam4() const {
return _yaw;
return yaw();
}
double getParam5() const {
return _x;
return latitude();
}
double getParam6() const {
return _y;
return longitude();
}
double getParam7() const {
return _z;
return altitude();
}
int getTurns() const {
return _param1;
......@@ -150,13 +158,6 @@ public:
int getAction() const {
return _action;
}
const QString& getName() const {
return _name;
}
const QString& getDescription() const {
return _description;
}
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
......@@ -166,47 +167,24 @@ public:
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
bool hasCoordinate(void);
QGeoCoordinate coordinate(void);
QString commandName(void);
signals:
void sequenceNumberChanged(int sequenceNumber);
void specifiesCoordinateChanged(bool specifiesCoordinate);
void isCurrentItemChanged(bool isCurrentItem);
void coordinateChanged(const QGeoCoordinate& coordinate);
void yawChanged(double yaw);
/** @brief Announces a change to the waypoint data */
void changed(MissionItem* wp);
MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)getAction(); };
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
QStringList valueLabels(void);
QStringList valueStrings(void);
void commandNameChanged(QString type);
void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void valueLabelsChanged(QStringList valueLabels);
void valueStringsChanged(QStringList valueStrings);
protected:
quint16 _id;
double _x;
double _y;
double _z;
double _yaw;
int _frame;
int _action;
bool _autocontinue;
bool _current;
double _orbit;
double _param1;
double _param2;
int _turns;
QString _name;
QString _description;
quint64 _reachedTime;
public:
void setId (quint16 _id);
void setX (double _x);
void setY (double _y);
void setZ (double _z);
void setLatitude (double lat);
void setLongitude (double lon);
void setAltitude (double alt);
/** @brief Yaw angle in COMPASS DEGREES: 0-360 */
void setYaw (int _yaw);
/** @brief Yaw angle in COMPASS DEGREES: 0-360 */
void setYaw (double _yaw);
/** @brief Set the waypoint action */
void setAction (int _action);
void setFrame (int _frame);
......@@ -234,22 +212,30 @@ public:
emit changed(this);
}
signals:
/** @brief Announces a change to the waypoint data */
void changed(MissionItem* wp);
void latitudeChanged ();
void longitudeChanged ();
void altitudeChanged ();
void hasCoordinateChanged(bool hasCoordinate);
void coordinateChanged(void);
void commandNameChanged(QString type);
void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void valueLabelsChanged(QStringList valueLabels);
void valueStringsChanged(QStringList valueStrings);
private:
QString _oneDecimalString(double value);
private:
typedef struct {
MAV_CMD command;
const char* name;
} MavCmd2Name_t;
int _sequenceNumber;
QGeoCoordinate _coordinate;
double _yaw;
int _frame;
int _action;
bool _autocontinue;
bool _isCurrentItem;
double _orbit;
double _param1;
double _param2;
int _turns;
quint64 _reachedTime;
static const int _cMavCmd2Name = 9;
static const MavCmd2Name_t _rgMavCmd2Name[_cMavCmd2Name];
};
#endif
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
/// Mission item edit control
Rectangle {
property var missionItem
width: _editFieldWidth + (ScreenTools.defaultFontPixelWidth * 10)
height: _valueColumn.y + _valueColumn.height + (radius / 2)
border.width: 2
border.color: "white"
color: "white"
radius: ScreenTools.defaultFontPixelWidth
readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 13
MissionItemIndexLabel {
id: _label
anchors.top: parent.top
anchors.right: parent.right
isCurrentItem: missionItem.isCurrentItem
label: missionItem.sequenceNumber
}
QGCComboBox {
id: _commandCombo
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.right: _label.left
anchors.top: parent.top
currentIndex: missionItem.commandByIndex
model: missionItem.commandNames
onActivated: missionItem.commandByIndex = index
}
Column {
id: _coordinateColumn
anchors.left: parent.left
anchors.right: parent.right
visible: missionItem.specifiesCoordinate
}
QGCTextField {
id: _latitudeField
anchors.margins: parent.radius / 2
anchors.top: _commandCombo.bottom
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.latitude
visible: missionItem.specifiesCoordinate
onAccepted: missionItem.coordinate.latitude = text
}
QGCTextField {
id: _longitudeField
anchors.margins: parent.radius / 2
anchors.top: _latitudeField.bottom
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.longitude
visible: missionItem.specifiesCoordinate
onAccepted: missionItem.coordinate.longtitude = text
}
QGCTextField {
id: _altitudeField
anchors.margins: parent.radius / 2
anchors.top: _longitudeField.bottom
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.altitude
visible: missionItem.specifiesCoordinate
showUnits: true
unitsLabel: "meters"
onAccepted: missionItem.coordinate.altitude = text
}
QGCLabel {
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.baseline: _latitudeField.baseline
color: "black"
text: "Lat:"
visible: missionItem.specifiesCoordinate
}
QGCLabel {
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.baseline: _longitudeField.baseline
color: "black"
text: "Long:"
visible: missionItem.specifiesCoordinate
}
QGCLabel {
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.baseline: _altitudeField.baseline
color: "black"
text: "Alt:"
visible: missionItem.specifiesCoordinate
}
Column {
id: _valueColumn
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.right: parent.right
anchors.top: missionItem.specifiesCoordinate ? _altitudeField.bottom : _commandCombo.bottom
Repeater {
model: missionItem.valueLabels
QGCLabel {
color: "black"
text: modelData
}
}
}
Column {
anchors.margins: parent.radius / 2
anchors.left: parent.left
anchors.right: parent.right
anchors.top: _valueColumn.top
Repeater {
model: missionItem.valueStrings
QGCLabel {
width: _valueColumn.width
color: "black"
text: modelData
horizontalAlignment: Text.AlignRight
}
}
}
}
......@@ -5,20 +5,21 @@ import QtQuick.Controls.Styles 1.2
import QGroundControl.ScreenTools 1.0
Rectangle {
property int missionItemIndex ///< Index to show in label
property alias label: _label.text
property bool isCurrentItem: false
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
border.width: 2
border.color: "white"
color: "orange"
color: isCurrentItem ? "green" : "orange"
QGCLabel {
id: _label
anchors.fill: parent
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
color: "white"
text: missionItemIndex
}
}
......@@ -7,7 +7,7 @@ import QGroundControl.Vehicle 1.0
/// Mission item summary display control
Rectangle {
property var missionItem ///< Mission Item object
property var missionItem ///< Mission Item object
width: ScreenTools.defaultFontPixelWidth * 15
height: valueColumn.height + radius
......@@ -17,9 +17,11 @@ Rectangle {
radius: ScreenTools.defaultFontPixelWidth
MissionItemIndexLabel {
id: _indexLabel
anchors.top: parent.top
anchors.right: parent.right
missionItemIndex: missionItem.id
isCurrentItem: missionItem.isCurrentItem
label: missionItem.sequenceNumber
}
Column {
......
......@@ -28,4 +28,5 @@ QGCViewMessage 1.0 QGCViewMessage.qml
MissionItemIndexLabel 1.0 MissionItemIndexLabel.qml
MissionItemSummary 1.0 MissionItemSummary.qml
MissionItemEditor 1.0 MissionItemEditor.qml
......@@ -708,7 +708,7 @@ void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/)
/*
bool changed = false;
for(int i = 0; i < _waypoints.count(); i++) {
if(_waypoints[i].getId() == wp->getId()) {
if(_waypoints[i].sequenceNumber() == wp->sequenceNumber()) {
_waypoints[i] = *wp;
changed = true;
break;
......
This diff is collapsed.
......@@ -1313,7 +1313,7 @@ void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float widt
float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
float acceptRadius = w->getAcceptanceRadius();
double yawDiff = w->getYaw()/180.0*M_PI-yaw;
double yawDiff = w->yaw()/180.0*M_PI-yaw;
// Draw background
pen.setColor(Qt::black);
......@@ -1356,11 +1356,11 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
int frameRef = w->getFrame();
if (frameRef == MAV_FRAME_LOCAL_NED)
{
in = QPointF(w->getX(), w->getY());
in = QPointF(w->x(), w->y());
}
else if (frameRef == MAV_FRAME_LOCAL_ENU)
{
in = QPointF(w->getY(), w->getX());
in = QPointF(w->y(), w->x());
}
// Convert global coordinates into the local ENU frame, then display them.
else if (frameRef == MAV_FRAME_GLOBAL || frameRef == MAV_FRAME_GLOBAL_RELATIVE_ALT) {
......@@ -1368,7 +1368,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
// Transform the lat/lon for this waypoint into the local frame
double e, n, u;
HomePositionManager::instance()->wgs84ToEnu(w->getX(), w->getY(),w->getZ(), &e, &n, &u);
HomePositionManager::instance()->wgs84ToEnu(w->x(), w->y(),w->z(), &e, &n, &u);
in = QPointF(n, e);
}
// Otherwise we don't process this waypoint.
......@@ -1383,7 +1383,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
QPointF p = metricBodyToRef(in);
// Select color based on if this is the current waypoint.
if (w->getCurrent())
if (w->isCurrentItem())
{
drawWaypoint(painter, QGC::colorYellow, refLineWidthToPen(0.8f), w, p);
}
......
......@@ -72,6 +72,7 @@ This file is part of the QGROUNDCONTROL project
#include "MultiVehicleManager.h"
#include "CustomCommandWidget.h"
#include "HomePositionManager.h"
#include "MissionEditor.h"
#ifdef UNITTEST_BUILD
#include "QmlControls/QmlTestWidget.h"
......@@ -425,6 +426,14 @@ void MainWindow::_buildPlanView(void)
}
}
void MainWindow::_buildMissionEditorView(void)
{
if (!_missionEditorView) {
_missionEditorView = new MissionEditor(this);
_missionEditorView->setVisible(false);
}
}
void MainWindow::_buildFlightView(void)
{
if (!_flightView) {
......@@ -700,6 +709,7 @@ void MainWindow::connectCommonActions()
perspectives->addAction(_ui.actionFlight);
perspectives->addAction(_ui.actionSimulationView);
perspectives->addAction(_ui.actionPlan);
perspectives->addAction(_ui.actionMissionEditor);
perspectives->addAction(_ui.actionSetup);
perspectives->setExclusive(true);
......@@ -724,6 +734,11 @@ void MainWindow::connectCommonActions()
_ui.actionPlan->setChecked(true);
_ui.actionPlan->activate(QAction::Trigger);
}
if (_currentView == VIEW_MISSIONEDITOR)
{
_ui.actionMissionEditor->setChecked(true);
_ui.actionMissionEditor->activate(QAction::Trigger);
}
if (_currentView == VIEW_SETUP)
{
_ui.actionSetup->setChecked(true);
......@@ -738,11 +753,12 @@ void MainWindow::connectCommonActions()
connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MainWindow::_vehicleRemoved);
// Views actions
connect(_ui.actionFlight, SIGNAL(triggered()), this, SLOT(loadFlightView()));
connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView()));
connect(_ui.actionAnalyze, SIGNAL(triggered()), this, SLOT(loadAnalyzeView()));
connect(_ui.actionPlan, SIGNAL(triggered()), this, SLOT(loadPlanView()));
connect(_ui.actionFlight, SIGNAL(triggered()), this, SLOT(loadFlightView()));
connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView()));
connect(_ui.actionAnalyze, SIGNAL(triggered()), this, SLOT(loadAnalyzeView()));
connect(_ui.actionPlan, SIGNAL(triggered()), this, SLOT(loadPlanView()));
connect(_ui.actionMissionEditor, SIGNAL(triggered()), this, SLOT(loadMissionEditorView()));
// Help Actions
connect(_ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(_ui.actionDeveloper_Credits, SIGNAL(triggered()), this, SLOT(showCredits()));
......@@ -891,6 +907,11 @@ void MainWindow::_loadCurrentViewState(void)
defaultWidgets = "WAYPOINT_LIST_DOCKWIDGET";
break;
case VIEW_MISSIONEDITOR:
_buildMissionEditorView();
centerView = _missionEditorView;
break;
case VIEW_SIMULATION:
_buildSimView();
centerView = _simView;
......@@ -993,6 +1014,17 @@ void MainWindow::loadPlanView()
}
}
void MainWindow::loadMissionEditorView()
{
if (_currentView != VIEW_MISSIONEDITOR)
{
_storeCurrentViewState();
_currentView = VIEW_MISSIONEDITOR;
_ui.actionMissionEditor->setChecked(true);
_loadCurrentViewState();
}
}
void MainWindow::loadSetupView()
{
if (_currentView != VIEW_SETUP)
......
......@@ -130,17 +130,13 @@ public slots:
/** @brief Show the application settings */
void showSettings();
/** @brief Load configuration views */
void loadSetupView();
/** @brief Load view for pilot */
void loadFlightView();
/** @brief Load view for simulation */
void loadSimulationView();
/** @brief Load view for engineer */
void loadAnalyzeView();
/** @brief Load New (QtQuick) Map View (Mission) */
void loadPlanView();
/** @brief Manage Links */
void loadMissionEditorView();
void manageLinks();
/** @brief Show the online help for users */
......@@ -204,12 +200,13 @@ protected:
typedef enum _VIEW_SECTIONS
{
VIEW_ANALYZE, // Engineering/Analyze view mode. Used for analyzing data and modifying onboard parameters
VIEW_PLAN, // New (QtQuick) Mission/Map/Plan view mode. Used for setting mission waypoints and high-level system commands.
VIEW_PLAN, // Old mission editor
VIEW_FLIGHT, // Flight/Fly/Operate view mode. Used for 1st-person observation of the vehicle.
VIEW_SIMULATION, // HIL Simulation view. Useful overview of the entire system when doing hardware-in-the-loop simulations.
VIEW_SETUP, // Setup view. Used for initializing the system for operation. Includes UI for calibration, firmware updating/checking, and parameter modifcation.
VIEW_UNUSED1, // Unused (don't remove, or it will screw up saved settigns indices)
VIEW_UNUSED2, // Unused (don't remove, or it will screw up saved settigns indices)
VIEW_MISSIONEDITOR, // New mission editor
} VIEW_SECTIONS;
/** @brief Catch window resize events */
......@@ -288,6 +285,7 @@ private:
QPointer<QWidget> _analyzeView;
QPointer<QWidget> _simView;
QPointer<QWidget> _terminalView;
QPointer<QWidget> _missionEditorView;
// Dock widget names
static const char* _uasControlDockWidgetName;
......@@ -316,6 +314,7 @@ private:
void _buildAnalyzeView(void);
void _buildSimView(void);
void _buildTerminalView(void);
void _buildMissionEditorView(void);
void _storeCurrentViewState(void);
void _loadCurrentViewState(void);
......@@ -344,7 +343,6 @@ private:
QString _getWindowStateKey();
QString _getWindowGeometryKey();
};
#endif /* _MAINWINDOW_H_ */
......@@ -79,6 +79,7 @@
</property>
<addaction name="actionSetup"/>
<addaction name="actionPlan"/>
<addaction name="actionMissionEditor"/>
<addaction name="actionFlight"/>
<addaction name="actionAnalyze"/>
<addaction name="separator"/>
......@@ -242,6 +243,17 @@
<string>Show Status Bar</string>
</property>
</action>
<action name="actionMissionEditor">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>New Mission Editor</string>
</property>
<property name="toolTip">
<string>Mission Editor</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -320,7 +320,7 @@ void WaypointEditableView::changedCurrent(int state)
{
if (state == 0)
{
if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current
if (wp->isCurrentItem() == true) //User clicked on the waypoint, that is already current
{
m_ui->selectedBox->setChecked(true);
m_ui->selectedBox->setCheckState(Qt::Checked);
......@@ -333,10 +333,10 @@ void WaypointEditableView::changedCurrent(int state)
}
else
{
wp->setCurrent(true);
wp->setIsCurrentItem(true);
// At this point we do not consider this signal
// to be valid / the edit check boxes should not change the view state
//emit changeCurrentWaypoint(wp->getId());
//emit changeCurrentWaypoint(wp->sequenceNumber());
//the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
}
}
......@@ -451,11 +451,11 @@ void WaypointEditableView::updateValues()
emit param7Broadcast(wp->getParam7());
if (m_ui->selectedBox->isChecked() != wp->getCurrent())
if (m_ui->selectedBox->isChecked() != wp->isCurrentItem())
{
// This is never a reason to emit a changed signal
m_ui->selectedBox->blockSignals(true);
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->selectedBox->setChecked(wp->isCurrentItem());
m_ui->selectedBox->blockSignals(false);
}
if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
......@@ -463,11 +463,11 @@ void WaypointEditableView::updateValues()
m_ui->autoContinue->setChecked(wp->getAutoContinue());
}
m_ui->idLabel->setText(QString::number(wp->getId()));
m_ui->idLabel->setText(QString::number(wp->sequenceNumber()));
// Style alternating rows of Missions as lighter/darker.
static int lastId = -1;
int currId = wp->getId() % 2;
int currId = wp->sequenceNumber() % 2;
if (currId != lastId)
{
if (currId == 1)
......
......@@ -272,13 +272,13 @@ void WaypointList::addEditable(bool onCurrentPosition)
wp->setFrame(frame);
if (frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{
wp->setLatitude(last->getLatitude());
wp->setLongitude(last->getLongitude());
wp->setAltitude(last->getAltitude());
wp->setLatitude(last->latitude());
wp->setLongitude(last->longitude());
wp->setAltitude(last->altitude());
} else {
wp->setX(last->getX());
wp->setY(last->getY());
wp->setZ(last->getZ());
wp->setX(last->x());
wp->setY(last->y());
wp->setZ(last->z());
}
wp->setParam1(last->getParam1());
wp->setParam2(last->getParam2());
......@@ -304,7 +304,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
} else {
updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint."));
}
wp = new MissionItem(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitudeAMSL(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(NULL, 0,
QGeoCoordinate(uas->getLatitude(), uas->getLongitude(), uas->getAltitudeAMSL()),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
} else {
......@@ -314,9 +316,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
} else {
updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint."));
}
wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(),
HomePositionManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(NULL, 0,
QGeoCoordinate(HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation()),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
......@@ -325,11 +327,15 @@ void WaypointList::addEditable(bool onCurrentPosition)
if (onCurrentPosition)
{
updateStatusLabel(tr("Added default LOCAL (NED) waypoint."));
wp = new MissionItem(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(NULL, 0,
QGeoCoordinate(uas->getLocalX(), uas->getLocalY(), uas->getLocalZ()),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
} else {
updateStatusLabel(tr("Added default LOCAL (NED) waypoint."));
wp = new MissionItem(0, 0, 0, -0.50, 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(0, 0,
QGeoCoordinate(0, 0, -0.50),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
......@@ -337,9 +343,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
// MAV connected, but position unknown, add default waypoint
updateStatusLabel(tr("WARNING: No position known. Adding default LOCAL (NED) waypoint"));
wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(),
HomePositionManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(NULL, 0,
QGeoCoordinate(HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation()),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
......@@ -347,9 +353,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
{
//Since no UAV available, create first default waypoint.
updateStatusLabel(tr("No UAV connected. Adding default GLOBAL (NED) waypoint"));
wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(),
HomePositionManager::instance()->getHomeLongitude(),
WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
wp = new MissionItem(NULL, 0,
QGeoCoordinate(HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation()),
0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
}
}
......@@ -389,7 +395,7 @@ void WaypointList::currentWaypointEditableChanged(quint16 seq)
WaypointEditableView* widget = wpEditableViews.value(waypoints[i], NULL);
if (widget) {
if (waypoints[i]->getId() == seq)
if (waypoints[i]->sequenceNumber() == seq)
{
widget->setCurrent(true);
}
......@@ -417,7 +423,7 @@ void WaypointList::currentWaypointViewOnlyChanged(quint16 seq)
WaypointViewOnlyView* widget = wpViewOnlyViews.value(waypoints[i], NULL);
if (widget) {
if (waypoints[i]->getId() == seq)
if (waypoints[i]->sequenceNumber() == seq)
{
widget->setCurrent(true);
}
......@@ -600,7 +606,7 @@ void WaypointList::moveDown(MissionItem* wp)
void WaypointList::removeWaypoint(MissionItem* wp)
{
WPM->removeWaypoint(wp->getId());
WPM->removeWaypoint(wp->sequenceNumber());
}
void WaypointList::changeEvent(QEvent *e)
......
This diff is collapsed.
......@@ -646,7 +646,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
// internals::PointLatLng coord = waypoint->Coord();
// QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6);
// qDebug() << "MAP WP COORD (MAP):" << coord_str << __FILE__ << __LINE__;
// QString wp_str = QString::number(wp->getLatitude(), 'f', 6) + " " + QString::number(wp->getLongitude(), 'f', 6);
// QString wp_str = QString::number(wp->getLatitude(), 'f', 6) + " " + QString::number(wp->longitude(), 'f', 6);
// qDebug() << "MAP WP COORD (WP):" << wp_str << __FILE__ << __LINE__;
// Protect from vicious double update cycle
......@@ -748,9 +748,9 @@ void QGCMapWidget::updateWaypoint(int uas, MissionItem* wp)
else
{
// Use safe standard interfaces for non MissionItem-class based wps
icon->SetCoord(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()));
icon->SetAltitude(wp->getAltitude());
icon->SetHeading(wp->getYaw());
icon->SetCoord(internals::PointLatLng(wp->latitude(), wp->longitude()));
icon->SetAltitude(wp->altitude());
icon->SetHeading(wp->yaw());
icon->SetNumber(wpindex);
}
// Re-enable signals again
......@@ -827,7 +827,7 @@ void QGCMapWidget::updateWaypointList(int uas)
// Update all potentially new waypoints
foreach (MissionItem* wp, wps)
{
qDebug() << "UPDATING NEW WP" << wp->getId();
qDebug() << "UPDATING NEW WP" << wp->sequenceNumber();
// Update / add only if new
if (!waypointsToIcons.contains(wp)) updateWaypoint(uas, wp);
}
......
......@@ -3,8 +3,8 @@
#include "opmapcontrol.h"
#include "QGC.h"
Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name, QString description, int radius)
: mapcontrol::WayPointItem(internals::PointLatLng(latitude, longitude), altitude, description, map),
Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name, int radius)
: mapcontrol::WayPointItem(internals::PointLatLng(latitude, longitude), altitude, QString(), map),
parent(parent),
waypoint(),
radius(radius),
......@@ -25,7 +25,7 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa
}
Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, MissionItem* wp, const QColor& color, int listindex, int radius)
: mapcontrol::WayPointItem(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()), wp->getAltitude(), wp->getDescription(), map),
: mapcontrol::WayPointItem(internals::PointLatLng(wp->latitude(), wp->longitude()), wp->altitude(), QString(), map),
parent(parent),
waypoint(wp),
radius(radius),
......@@ -33,7 +33,7 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa
showOrbit(false),
color(color)
{
SetHeading(wp->getYaw());
SetHeading(wp->yaw());
SetNumber(listindex);
this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
picture = QPixmap(radius+1, radius+1);
......@@ -59,13 +59,12 @@ void Waypoint2DIcon::updateWaypoint()
// Store old size
static QRectF oldSize;
SetHeading(waypoint->getYaw());
SetCoord(internals::PointLatLng(waypoint->getLatitude(), waypoint->getLongitude()));
SetHeading(waypoint->yaw());
SetCoord(internals::PointLatLng(waypoint->latitude(), waypoint->longitude()));
// qDebug() << "UPDATING WP:" << waypoint->getId() << "LAT:" << waypoint->getLatitude() << "LON:" << waypoint->getLongitude();
// qDebug() << "UPDATING WP:" << waypoint->sequenceNumber() << "LAT:" << waypoint->latitude() << "LON:" << waypoint->longitude();
SetDescription(waypoint->getDescription());
SetAltitude(waypoint->getAltitude());
SetAltitude(waypoint->altitude());
// FIXME Add SetNumber (currently needs a separate call)
drawIcon();
QRectF newSize = boundingRect();
......
......@@ -15,7 +15,7 @@ public:
* @param longitude
* @param name name of the circle point
*/
Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name = QString(), QString description = QString(), int radius=30);
Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, qreal latitude, qreal longitude, qreal altitude, int listindex, QString name = QString(), int radius=30);
/**
*
......
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