diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 1ab4651b3a5e495582d31fde03559a69d9a907ac..117e51de5cdad1286e0aba24a76177f33635261c 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -100,6 +100,7 @@
src/QmlControls/ModeSwitchDisplay.qml
src/QmlControls/MissionItemIndexLabel.qml
src/QmlControls/MissionItemSummary.qml
+ src/QmlControls/MissionItemEditor.qml
src/VehicleSetup/SetupView.qml
@@ -151,7 +152,7 @@
src/FlightMap/Widgets/QGCWaypointEditor.qml
- src/FlightMap/MapItems/MissionMapItem.qml
+ src/FlightMap/MapItems/MissionItemIndicator.qml
src/FlightMap/MapItems/VehicleMapItem.qml
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index 4a139203a7b6bb2e6cc086477fd49974738c3c70..dafc57dd9e36021caedad5fff2c7e2deb310a0d0 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -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
}
}
diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml
index bf2d7d4dadd97181aeb4bbcc5dbeceb8449d57b5..f13516ab5e17fdfbcc92b8fbbba07df4b2005cfa 100644
--- a/src/FlightMap/FlightMap.qml
+++ b/src/FlightMap/FlightMap.qml
@@ -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);
diff --git a/src/FlightMap/MapItems/MissionMapItem.qml b/src/FlightMap/MapItems/MissionItemIndicator.qml
similarity index 90%
rename from src/FlightMap/MapItems/MissionMapItem.qml
rename to src/FlightMap/MapItems/MissionItemIndicator.qml
index c2bdf22b403119e75138129987816a7214a4ba36..8036cb1151120a28b8bbe08fc39300ee2c26ac05 100644
--- a/src/FlightMap/MapItems/MissionMapItem.qml
+++ b/src/FlightMap/MapItems/MissionItemIndicator.qml
@@ -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
}
}
diff --git a/src/FlightMap/qmldir b/src/FlightMap/qmldir
index 31105f448d45d239307e634e1e03ec3e20046af1..5ab3544a98cdb7e42dfe495a4a00e9f95d34760a 100644
--- a/src/FlightMap/qmldir
+++ b/src/FlightMap/qmldir
@@ -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
diff --git a/src/MissionEditor/MissionEditor.cc b/src/MissionEditor/MissionEditor.cc
index d50d572d5f9d99e45edc229551bc46c05383590d..91b2281774432f712cf99542eb05fe5a1ea00f3c 100644
--- a/src/MissionEditor/MissionEditor.cc
+++ b/src/MissionEditor/MissionEditor.cc
@@ -73,6 +73,10 @@ QString MissionEditor::loadSetting(const QString &name, const QString& defaultVa
void MissionEditor::addMissionItem(QGeoCoordinate coordinate)
{
- MissionItem * newItem = new MissionItem(this, _missionItems.count(), coordinate.longitude(), coordinate.latitude());
+ 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);
}
diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml
index b7ebb79e87c113e909898df50ded090997514f8f..e5f0e9c842a99ea17b875aecb75a6b4b2b9024e2 100644
--- a/src/MissionEditor/MissionEditor.qml
+++ b/src/MissionEditor/MissionEditor.qml
@@ -21,10 +21,11 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
-import QtQuick 2.4
-import QtQuick.Controls 1.3
-import QtQuick.Controls.Styles 1.2
-import QtQuick.Dialogs 1.2
+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
@@ -32,64 +33,83 @@ import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
/// Mission Editor
+
Item {
- id: root
+ // 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.
- property var __qgcPal: QGCPalette { colorGroupEnabled: enabled }
+ readonly property real _defaultLatitude: 37.803784
+ readonly property real _defaultLongitude: -122.462276
+ readonly property int _decimalPlaces: 7
- property var _activeVehicle: multiVehicleManager.activeVehicle
+ FlightMap {
+ id: editorMap
+ anchors.fill: parent
+ mapName: "MissionEditor"
+ latitude: _defaultLatitude
+ longitude: _defaultLongitude
- readonly property real _defaultLatitude: 37.803784
- readonly property real _defaultLongitude: -122.462276
+ QGCLabel { text: "WIP: Non functional"; font.pixelSize: ScreenTools.largeFontPixelSize }
- FlightMap {
- id: editorMap
- anchors.fill: parent
- mapName: "MissionEditor"
- latitude: parent._defaultLatitude
- longitude: parent._defaultLongitude
MouseArea {
anchors.fill: parent
- onClicked: controller.addMissionItem(editorMap.mapItem.toCoordinate(Qt.point(mouse.x, mouse.y)))
+ 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)
+ }
}
- }
- 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
+ // 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
+ }
}
- }
- // Mission item list
- ListView {
- id: missionItemSummaryList
- anchors.margins: ScreenTools.defaultFontPixelWidth
- anchors.bottom: parent.bottom
- width: parent.width
- height: ScreenTools.defaultFontPixelHeight * 7
- spacing: ScreenTools.defaultFontPixelWidth / 2
- opacity: 0.75
- orientation: ListView.Horizontal
- model: controller.missionItems
-
- property real _maxItemHeight: 0
-
- delegate:
- MissionItemSummary {
- opacity: 0.75
- missionItem: object
-Component.onCompleted: console.log("add", object.id)
+ 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
}
+ }
}
-
}
diff --git a/src/MissionItem.cc b/src/MissionItem.cc
index d613a8244d6fedda0058588167fac3a96fb1b42b..1be08bb9257ef2932db7484d9a96d16f7589dfe2 100644
--- a/src/MissionItem.cc
+++ b/src/MissionItem.cc
@@ -34,41 +34,43 @@ This file is part of the QGROUNDCONTROL project
#include "MissionItem.h"
-MissionItem::MissionItem(
- QObject *parent,
- quint16 id,
- double x,
- double y,
- double z,
- double param1,
- double param2,
- double param3,
- double param4,
- bool autocontinue,
- bool current,
- int frame,
- int action,
- const QString& description
- )
+const MissionItem::MavCmd2Name_t MissionItem::_rgMavCmd2Name[_cMavCmd2Name] = {
+ { MAV_CMD_NAV_WAYPOINT, "Waypoint" },
+ { MAV_CMD_NAV_LOITER_UNLIM, "Loiter" },
+ { MAV_CMD_NAV_LOITER_TURNS, "Loiter (turns)" },
+ { MAV_CMD_NAV_LOITER_TIME, "Loiter (unlimited)" },
+ { MAV_CMD_NAV_RETURN_TO_LAUNCH, "Return Home" },
+ { MAV_CMD_NAV_LAND, "Land" },
+ { MAV_CMD_NAV_TAKEOFF, "Takeoff" },
+ { MAV_CMD_CONDITION_DELAY, "Delay" },
+ { MAV_CMD_DO_JUMP, "Jump To Command" },
+};
+
+MissionItem::MissionItem(QObject* parent,
+ int sequenceNumber,
+ QGeoCoordinate coordinate,
+ double param1,
+ double param2,
+ double param3,
+ double param4,
+ bool autocontinue,
+ bool isCurrentItem,
+ int frame,
+ int action)
: QObject(parent)
- , _id(id)
- , _x(x)
- , _y(y)
- , _z(z)
+ , _sequenceNumber(sequenceNumber)
+ , _coordinate(coordinate)
, _yaw(param4)
, _frame(frame)
, _action(action)
, _autocontinue(autocontinue)
- , _current(current)
+ , _isCurrentItem(isCurrentItem)
, _orbit(param3)
, _param1(param1)
, _param2(param2)
- , _name(QString("WP%1").arg(id, 2, 10, QChar('0')))
- , _description(description)
, _reachedTime(0)
{
- connect(this, &MissionItem::latitudeChanged, this, &MissionItem::coordinateChanged);
- connect(this, &MissionItem::longitudeChanged, this, &MissionItem::coordinateChanged);
+
}
MissionItem::MissionItem(const MissionItem& other)
@@ -83,21 +85,18 @@ MissionItem::~MissionItem()
const MissionItem& MissionItem::operator=(const MissionItem& other)
{
- _id = other.getId();
- _x = other.getX();
- _y = other.getY();
- _z = other.getZ();
- _yaw = other.getYaw();
- _frame = other.getFrame();
- _action = other.getAction();
- _autocontinue = other.getAutoContinue();
- _current = other.getCurrent();
- _orbit = other.getParam3();
- _param1 = other.getParam1();
- _param2 = other.getParam2();
- _name = other.getName();
- _description = other.getDescription();
- _reachedTime = other.getReachedTime();
+ _sequenceNumber = other._sequenceNumber;
+ _isCurrentItem = other._isCurrentItem;
+ _coordinate = other._coordinate;
+ _yaw = other._yaw;
+ _frame = other._frame;
+ _action = other._action;
+ _autocontinue = other._autocontinue;
+ _orbit = other._orbit;
+ _param1 = other._param1;
+ _param2 = other._param2;
+ _reachedTime = other._reachedTime;
+
return *this;
}
@@ -109,43 +108,42 @@ bool MissionItem::isNavigationType()
void MissionItem::save(QTextStream &saveStream)
{
QString position("%1\t%2\t%3");
- position = position.arg(_x, 0, 'g', 18);
- position = position.arg(_y, 0, 'g', 18);
- position = position.arg(_z, 0, 'g', 18);
+ position = position.arg(x(), 0, 'g', 18);
+ position = position.arg(y(), 0, 'g', 18);
+ position = position.arg(z(), 0, 'g', 18);
QString parameters("%1\t%2\t%3\t%4");
parameters = parameters.arg(_param1, 0, 'g', 18).arg(_param2, 0, 'g', 18).arg(_orbit, 0, 'g', 18).arg(_yaw, 0, 'g', 18);
// FORMAT:
// as documented here: http://qgroundcontrol.org/waypoint_protocol
- saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n";
+ saveStream << this->sequenceNumber() << "\t" << this->isCurrentItem() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n";
}
bool MissionItem::load(QTextStream &loadStream)
{
const QStringList &wpParams = loadStream.readLine().split("\t");
if (wpParams.size() == 12) {
- _id = wpParams[0].toInt();
- _current = (wpParams[1].toInt() == 1 ? true : false);
+ setSequenceNumber(wpParams[0].toInt());
+ setIsCurrentItem(wpParams[1].toInt() == 1 ? true : false);
_frame = (MAV_FRAME) wpParams[2].toInt();
_action = (MAV_CMD) wpParams[3].toInt();
_param1 = wpParams[4].toDouble();
_param2 = wpParams[5].toDouble();
_orbit = wpParams[6].toDouble();
- _yaw = wpParams[7].toDouble();
- _x = wpParams[8].toDouble();
- _y = wpParams[9].toDouble();
- _z = wpParams[10].toDouble();
+ setYaw(wpParams[7].toDouble());
+ setLatitude(wpParams[8].toDouble());
+ setLongitude(wpParams[9].toDouble());
+ setAltitude(wpParams[10].toDouble());
_autocontinue = (wpParams[11].toInt() == 1 ? true : false);
- //_description = wpParams[12];
return true;
}
return false;
}
-void MissionItem::setId(quint16 id)
+void MissionItem::setSequenceNumber(int sequenceNumber)
{
- _id = id;
- _name = QString("WP%1").arg(id, 2, 10, QChar('0'));
+ _sequenceNumber = sequenceNumber;
+ emit sequenceNumberChanged(_sequenceNumber);
emit changed(this);
}
@@ -153,8 +151,7 @@ void MissionItem::setX(double x)
{
if (!isinf(x) && !isnan(x) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU)))
{
- _x = x;
- emit changed(this);
+ setLatitude(x);
}
}
@@ -162,8 +159,7 @@ void MissionItem::setY(double y)
{
if (!isinf(y) && !isnan(y) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU)))
{
- _y = y;
- emit changed(this);
+ setLongitude(y);
}
}
@@ -171,49 +167,38 @@ void MissionItem::setZ(double z)
{
if (!isinf(z) && !isnan(z) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU)))
{
- _z = z;
- emit changed(this);
+ setAltitude(z);
}
}
void MissionItem::setLatitude(double lat)
{
- if (_x != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
+ if (_coordinate.latitude() != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{
- _x = lat;
+ _coordinate.setLatitude(lat);
emit changed(this);
- emit coordinateChanged();
+ emit coordinateChanged(coordinate());
}
}
void MissionItem::setLongitude(double lon)
{
- if (_y != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
+ if (_coordinate.longitude() != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{
- _y = lon;
+ _coordinate.setLongitude(lon);
emit changed(this);
- emit coordinateChanged();
+ emit coordinateChanged(coordinate());
}
}
void MissionItem::setAltitude(double altitude)
{
- if (_z != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
+ if (_coordinate.altitude() != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{
- _z = altitude;
- emit changed(this);
- emit valueStringsChanged(valueStrings());
- emit coordinateChanged();
- }
-}
-
-void MissionItem::setYaw(int yaw)
-{
- if (_yaw != yaw)
- {
- _yaw = yaw;
+ _coordinate.setAltitude(altitude);
emit changed(this);
emit valueStringsChanged(valueStrings());
+ emit coordinateChanged(coordinate());
}
}
@@ -222,6 +207,7 @@ void MissionItem::setYaw(double yaw)
if (_yaw != yaw)
{
_yaw = yaw;
+ emit yawChanged(yaw);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
@@ -242,7 +228,7 @@ void MissionItem::setAction(int /*MAV_CMD*/ action)
emit changed(this);
emit commandNameChanged(commandName());
emit commandChanged((MavlinkQmlSingleton::Qml_MAV_CMD)_action);
- emit hasCoordinateChanged(hasCoordinate());
+ emit specifiesCoordinateChanged(specifiesCoordinate());
emit valueLabelsChanged(valueLabels());
emit valueStringsChanged(valueStrings());
}
@@ -264,13 +250,11 @@ void MissionItem::setAutocontinue(bool autoContinue)
}
}
-void MissionItem::setCurrent(bool current)
+void MissionItem::setIsCurrentItem(bool isCurrentItem)
{
- if (_current != current)
- {
- _current = current;
- // The current waypoint index is handled by the list
- // and not part of the individual waypoint update state
+ if (_isCurrentItem != isCurrentItem) {
+ _isCurrentItem = isCurrentItem;
+ emit isCurrentItemChanged(isCurrentItem);
}
}
@@ -326,8 +310,8 @@ void MissionItem::setParam4(double param4)
void MissionItem::setParam5(double param5)
{
- if (_x != param5) {
- _x = param5;
+ if (_coordinate.latitude() != param5) {
+ _coordinate.setLatitude(param5);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
@@ -335,8 +319,8 @@ void MissionItem::setParam5(double param5)
void MissionItem::setParam6(double param6)
{
- if (_y != param6) {
- _y = param6;
+ if (_coordinate.longitude() != param6) {
+ _coordinate.setLongitude(param6);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
@@ -344,8 +328,8 @@ void MissionItem::setParam6(double param6)
void MissionItem::setParam7(double param7)
{
- if (_z != param7) {
- _z = param7;
+ if (_coordinate.altitude() != param7) {
+ _coordinate.setAltitude(param7);
emit valueStringsChanged(valueStrings());
emit changed(this);
}
@@ -387,7 +371,7 @@ void MissionItem::setTurns(int turns)
}
}
-bool MissionItem::hasCoordinate(void)
+bool MissionItem::specifiesCoordinate(void) const
{
switch (_action) {
case MAV_CMD_NAV_WAYPOINT:
@@ -402,11 +386,6 @@ bool MissionItem::hasCoordinate(void)
}
}
-QGeoCoordinate MissionItem::coordinate(void)
-{
- return QGeoCoordinate(_x, _y);
-}
-
QString MissionItem::commandName(void)
{
QString type;
@@ -507,7 +486,7 @@ QStringList MissionItem::valueStrings(void)
switch (_action) {
case MAV_CMD_NAV_WAYPOINT:
- list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param2) << _oneDecimalString(_param1);
+ list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param2) << _oneDecimalString(_param1);
break;
case MAV_CMD_NAV_LOITER_UNLIM:
list << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_orbit);
@@ -521,10 +500,10 @@ QStringList MissionItem::valueStrings(void)
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
break;
case MAV_CMD_NAV_LAND:
- list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI));
+ list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(_yaw * (180.0 / M_PI));
break;
case MAV_CMD_NAV_TAKEOFF:
- list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param1);
+ list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param1);
break;
case MAV_CMD_CONDITION_DELAY:
list << _oneDecimalString(_param1);
@@ -537,4 +516,42 @@ QStringList MissionItem::valueStrings(void)
}
return list;
-}
\ No newline at end of file
+}
+
+void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
+{
+ _coordinate = coordinate;
+ emit coordinateChanged(coordinate);
+ emit changed(this);
+}
+
+QStringList MissionItem::commandNames(void) {
+ QStringList list;
+
+ for (int i=0; i<_cMavCmd2Name; i++) {
+ list += _rgMavCmd2Name[i].name;
+ }
+
+ return list;
+}
+
+int MissionItem::commandByIndex(void)
+{
+ for (int i=0; i<_cMavCmd2Name; i++) {
+ if (_rgMavCmd2Name[i].command == _action) {
+ return i;
+ }
+ }
+
+ return -1;
+}
+
+void MissionItem::setCommandByIndex(int index)
+{
+ if (index < 0 || index >= _cMavCmd2Name) {
+ qWarning() << "Invalid index" << index;
+ return;
+ }
+
+ setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)_rgMavCmd2Name[index].command);
+}
diff --git a/src/MissionItem.h b/src/MissionItem.h
index 84fb83c2cc70426ef3d2ff8c2b7b97e89781108d..300ac3d7f4da38268e3daddfc7e4e681f8e2b9d4 100644
--- a/src/MissionItem.h
+++ b/src/MissionItem.h
@@ -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
diff --git a/src/QmlControls/MissionItemEditor.qml b/src/QmlControls/MissionItemEditor.qml
new file mode 100644
index 0000000000000000000000000000000000000000..b6f32e61195e1fd7236f0ac96e9af5a31b22faf8
--- /dev/null
+++ b/src/QmlControls/MissionItemEditor.qml
@@ -0,0 +1,148 @@
+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
+ }
+ }
+ }
+}
diff --git a/src/QmlControls/MissionItemIndexLabel.qml b/src/QmlControls/MissionItemIndexLabel.qml
index cf4f496e3132869945116889d9b36745ad25f0dd..a5f9b87f024811f3560f7a4308d652974cb5ca6d 100644
--- a/src/QmlControls/MissionItemIndexLabel.qml
+++ b/src/QmlControls/MissionItemIndexLabel.qml
@@ -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
}
}
diff --git a/src/QmlControls/MissionItemSummary.qml b/src/QmlControls/MissionItemSummary.qml
index f8754129a6dfcceb1db3339370e14e3106c205b2..630cfb821b3999b0060fe45864091d7bee65856d 100644
--- a/src/QmlControls/MissionItemSummary.qml
+++ b/src/QmlControls/MissionItemSummary.qml
@@ -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 {
diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir
index 511d4d9d4a32473d9c00f7e7936f85512acbad41..62674c353b4c63ca22a9d628fe133080831d8eb8 100644
--- a/src/QmlControls/QGroundControl.Controls.qmldir
+++ b/src/QmlControls/QGroundControl.Controls.qmldir
@@ -28,4 +28,5 @@ QGCViewMessage 1.0 QGCViewMessage.qml
MissionItemIndexLabel 1.0 MissionItemIndexLabel.qml
MissionItemSummary 1.0 MissionItemSummary.qml
+MissionItemEditor 1.0 MissionItemEditor.qml
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 5ca6f7639580f608c42afbf5593014bf728c1b98..d692b520b3eb3f9836a3901b2a357f89de3b3e14 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -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;
diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc
index 548ca291628e0fee9e65f47310085924d368eb72..41516446f34a58ea19e3ee6f2952b06dbb85a508 100644
--- a/src/uas/UASWaypointManager.cc
+++ b/src/uas/UASWaypointManager.cc
@@ -116,9 +116,9 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x,
Q_UNUSED(time);
if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU))
{
- double xdiff = x-currentWaypointEditable->getX();
- double ydiff = y-currentWaypointEditable->getY();
- double zdiff = z-currentWaypointEditable->getZ();
+ double xdiff = x-currentWaypointEditable->x();
+ double ydiff = y-currentWaypointEditable->y();
+ double zdiff = z-currentWaypointEditable->z();
double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
emit waypointDistanceChanged(dist);
}
@@ -196,37 +196,32 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id) {
- MissionItem *lwp_vo = new MissionItem(
- NULL,
- wp->seq, wp->x,
- wp->y,
- wp->z,
- wp->param1,
- wp->param2,
- wp->param3,
- wp->param4,
- wp->autocontinue,
- wp->current,
- (MAV_FRAME) wp->frame,
- (MAV_CMD) wp->command);
+ MissionItem *lwp_vo = new MissionItem(NULL,
+ wp->seq,
+ QGeoCoordinate(wp->x, wp->y, wp->z),
+ wp->param1,
+ wp->param2,
+ wp->param3,
+ wp->param4,
+ wp->autocontinue,
+ wp->current,
+ (MAV_FRAME) wp->frame,
+ (MAV_CMD) wp->command);
addWaypointViewOnly(lwp_vo);
if (read_to_edit == true) {
- MissionItem *lwp_ed = new MissionItem(
- NULL,
- wp->seq,
- wp->x,
- wp->y,
- wp->z,
- wp->param1,
- wp->param2,
- wp->param3,
- wp->param4,
- wp->autocontinue,
- wp->current,
- (MAV_FRAME) wp->frame,
- (MAV_CMD) wp->command);
+ MissionItem *lwp_ed = new MissionItem(NULL,
+ wp->seq,
+ QGeoCoordinate(wp->x, wp->y, wp->z),
+ wp->param1,
+ wp->param2,
+ wp->param3,
+ wp->param4,
+ wp->autocontinue,
+ wp->current,
+ (MAV_FRAME) wp->frame,
+ (MAV_CMD) wp->command);
addWaypointEditable(lwp_ed, false);
if (wp->current == 1) currentWaypointEditable = lwp_ed;
}
@@ -258,20 +253,17 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
&& wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) {
// accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
// but only update view only side
- MissionItem *lwp_vo = new MissionItem(
- NULL,
- wp->seq,
- wp->x,
- wp->y,
- wp->z,
- wp->param1,
- wp->param2,
- wp->param3,
- wp->param4,
- wp->autocontinue,
- wp->current,
- (MAV_FRAME) wp->frame,
- (MAV_CMD) wp->command);
+ MissionItem *lwp_vo = new MissionItem(NULL,
+ wp->seq,
+ QGeoCoordinate(wp->x, wp->y, wp->z),
+ wp->param1,
+ wp->param2,
+ wp->param3,
+ wp->param4,
+ wp->autocontinue,
+ wp->current,
+ (MAV_FRAME) wp->frame,
+ (MAV_CMD) wp->command);
waypointsViewOnly.replace(wp->seq, lwp_vo);
emit waypointViewOnlyListChanged();
@@ -386,10 +378,10 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
// update the local main storage
if (wpc->seq < waypointsViewOnly.size()) {
for(int i = 0; i < waypointsViewOnly.size(); i++) {
- if (waypointsViewOnly[i]->getId() == wpc->seq) {
- waypointsViewOnly[i]->setCurrent(true);
+ if (waypointsViewOnly[i]->sequenceNumber() == wpc->seq) {
+ waypointsViewOnly[i]->setIsCurrentItem(true);
} else {
- waypointsViewOnly[i]->setCurrent(false);
+ waypointsViewOnly[i]->setIsCurrentItem(false);
}
}
}
@@ -450,10 +442,10 @@ int UASWaypointManager::setCurrentEditable(quint16 seq)
if(current_state == WP_IDLE) {
//update local main storage
for (int i = 0; i < waypointsEditable.count(); i++) {
- if (waypointsEditable[i]->getId() == seq) {
- waypointsEditable[i]->setCurrent(true);
+ if (waypointsEditable[i]->sequenceNumber() == seq) {
+ waypointsEditable[i]->setIsCurrentItem(true);
} else {
- waypointsEditable[i]->setCurrent(false);
+ waypointsEditable[i]->setIsCurrentItem(false);
}
}
@@ -490,10 +482,10 @@ void UASWaypointManager::addWaypointEditable(MissionItem *wp, bool enforceFirstA
QGCMessageBox::critical(tr("MissionItem Manager"), _offlineEditingModeMessage);
}
- wp->setId(waypointsEditable.count());
+ wp->setSequenceNumber(waypointsEditable.count());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
- wp->setCurrent(true);
+ wp->setIsCurrentItem(true);
currentWaypointEditable = wp;
}
waypointsEditable.insert(waypointsEditable.count(), wp);
@@ -515,13 +507,13 @@ MissionItem* UASWaypointManager::createWaypoint(bool enforceFirstActive)
}
MissionItem* wp = new MissionItem();
- wp->setId(waypointsEditable.count());
+ wp->setSequenceNumber(waypointsEditable.count());
wp->setFrame((MAV_FRAME)getFrameRecommendation());
wp->setAltitude(getAltitudeRecommendation());
wp->setAcceptanceRadius(getAcceptanceRadiusRecommendation());
if (enforceFirstActive && waypointsEditable.count() == 0)
{
- wp->setCurrent(true);
+ wp->setIsCurrentItem(true);
currentWaypointEditable = wp;
}
waypointsEditable.append(wp);
@@ -538,15 +530,15 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
{
MissionItem *t = waypointsEditable[seq];
- if (t->getCurrent() == true) //trying to remove the current waypoint
+ if (t->isCurrentItem() == true) //trying to remove the current waypoint
{
if (seq+1 < waypointsEditable.count()) // setting the next waypoint as current
{
- waypointsEditable[seq+1]->setCurrent(true);
+ waypointsEditable[seq+1]->setIsCurrentItem(true);
}
else if (seq-1 >= 0) // if deleting the last on the list, then setting the previous waypoint as current
{
- waypointsEditable[seq-1]->setCurrent(true);
+ waypointsEditable[seq-1]->setIsCurrentItem(true);
}
}
@@ -556,7 +548,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
for(int i = seq; i < waypointsEditable.count(); i++)
{
- waypointsEditable[i]->setId(i);
+ waypointsEditable[i]->setSequenceNumber(i);
}
emit waypointEditableListChanged();
@@ -575,7 +567,7 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
for (int i = cur_seq; i < new_seq; i++)
{
waypointsEditable[i] = waypointsEditable[i+1];
- waypointsEditable[i]->setId(i);
+ waypointsEditable[i]->setSequenceNumber(i);
}
}
else
@@ -583,11 +575,11 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
for (int i = cur_seq; i > new_seq; i--)
{
waypointsEditable[i] = waypointsEditable[i-1];
- waypointsEditable[i]->setId(i);
+ waypointsEditable[i]->setSequenceNumber(i);
}
}
waypointsEditable[new_seq] = t;
- waypointsEditable[new_seq]->setId(new_seq);
+ waypointsEditable[new_seq]->setSequenceNumber(new_seq);
emit waypointEditableListChanged();
emit waypointEditableListChanged(uasid);
@@ -607,7 +599,7 @@ void UASWaypointManager::saveWaypoints(const QString &saveFile)
for (int i = 0; i < waypointsEditable.count(); i++)
{
- waypointsEditable[i]->setId(i);
+ waypointsEditable[i]->setSequenceNumber(i);
waypointsEditable[i]->save(out);
}
file.close();
@@ -642,7 +634,7 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
{
//Use the existing function to add waypoints to the map instead of doing it manually
//Indeed, we should connect our waypoints to the map in order to synchronize them
- //t->setId(waypointsEditable.count());
+ //t->setSequenceNumber(waypointsEditable.count());
// waypointsEditable.insert(waypointsEditable.count(), t);
addWaypointEditable(t, false);
}
@@ -956,9 +948,9 @@ void UASWaypointManager::goToWaypoint(MissionItem *wp)
mission.frame = wp->getFrame();
mission.command = wp->getAction();
mission.seq = 0; // don't read out the sequence number of the waypoint class
- mission.x = wp->getX();
- mission.y = wp->getY();
- mission.z = wp->getZ();
+ mission.x = wp->x();
+ mission.y = wp->y();
+ mission.z = wp->z();
mavlink_message_t message;
mission.target_system = uasid;
mission.target_component = MAV_COMP_ID_MISSIONPLANNER;
@@ -1001,7 +993,7 @@ void UASWaypointManager::writeWaypoints()
const MissionItem *cur_s = waypointsEditable.at(i);
cur_d->autocontinue = cur_s->getAutoContinue();
- cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
+ cur_d->current = cur_s->isCurrentItem() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->param1 = cur_s->getParam1();
cur_d->param2 = cur_s->getParam2();
cur_d->param3 = cur_s->getParam3();
@@ -1009,11 +1001,11 @@ void UASWaypointManager::writeWaypoints()
cur_d->frame = cur_s->getFrame();
cur_d->command = cur_s->getAction();
cur_d->seq = i; // don't read out the sequence number of the waypoint class
- cur_d->x = cur_s->getX();
- cur_d->y = cur_s->getY();
- cur_d->z = cur_s->getZ();
+ cur_d->x = cur_s->x();
+ cur_d->y = cur_s->y();
+ cur_d->z = cur_s->z();
- if (cur_s->getCurrent() && noCurrent)
+ if (cur_s->isCurrentItem() && noCurrent)
noCurrent = false;
if (i == (current_count - 1) && noCurrent == true) //not a single waypoint was set as "current"
cur_d->current = true; // set the last waypoint as current. Or should it better be the first waypoint ?
@@ -1162,7 +1154,7 @@ UAS* UASWaypointManager::getUAS() {
float UASWaypointManager::getAltitudeRecommendation()
{
if (waypointsEditable.count() > 0) {
- return waypointsEditable.last()->getAltitude();
+ return waypointsEditable.last()->altitude();
} else {
return HomePositionManager::instance()->getHomeAltitude() + getHomeAltitudeOffsetDefault();
}
diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc
index 3df5d60c19130c7abfb652b059334df78b601934..0e46b297ed5b0344121d8255a9a888fc8d2535dc 100644
--- a/src/ui/HSIDisplay.cc
+++ b/src/ui/HSIDisplay.cc
@@ -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);
}
diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc
index 3ceb42e05de9343534e69bae8ce99dad98d83988..9974a0787e19f4f644e8426b528f181cc25d8837 100644
--- a/src/ui/WaypointEditableView.cc
+++ b/src/ui/WaypointEditableView.cc
@@ -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)
diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc
index c7f7a9a3b7e9ce2d5251927aebdfb2a8e716779f..fe13b9f453be46b83b8db3126743bc01248bccbf 100644
--- a/src/ui/WaypointList.cc
+++ b/src/ui/WaypointList.cc
@@ -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)
diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc
index 2beb63be10ead32c04498613254b4b058f8f3ff9..b3319e7daca14bcb6bd40a66dc9670229078e07f 100644
--- a/src/ui/WaypointViewOnlyView.cc
+++ b/src/ui/WaypointViewOnlyView.cc
@@ -24,19 +24,19 @@ void WaypointViewOnlyView::changedAutoContinue(int state)
new_value = true;
}
wp->setAutocontinue(new_value);
- emit changeAutoContinue(wp->getId(),new_value);
+ emit changeAutoContinue(wp->sequenceNumber(),new_value);
}
void WaypointViewOnlyView::changedCurrent(int state)
//This is a slot receiving signals from QCheckBox m_ui->current. The state given here is whatever the user has clicked and not the true "current" value onboard.
{
Q_UNUSED(state);
- //qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
+ //qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->sequenceNumber();
m_ui->current->blockSignals(true);
if (m_ui->current->isChecked() == false)
{
- if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current. Box stays checked
+ if (wp->isCurrentItem() == true) //User clicked on the waypoint, that is already current. Box stays checked
{
m_ui->current->setCheckState(Qt::Checked);
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Rechecked true. stay true " << m_ui->current->isChecked();
@@ -51,7 +51,7 @@ void WaypointViewOnlyView::changedCurrent(int state)
{
m_ui->current->setCheckState(Qt::Unchecked);
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Checked new. Sending set_current request to Manager " << m_ui->current->isChecked();
- emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
+ emit changeCurrentWaypoint(wp->sequenceNumber()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
}
m_ui->current->blockSignals(false);
@@ -67,12 +67,12 @@ void WaypointViewOnlyView::setCurrent(bool state)
m_ui->current->blockSignals(true);
if (state == true)
{
- wp->setCurrent(true);
+ wp->setIsCurrentItem(true);
m_ui->current->setCheckState(Qt::Checked);
}
else
{
- wp->setCurrent(false);
+ wp->setIsCurrentItem(false);
m_ui->current->setCheckState(Qt::Unchecked);
}
m_ui->current->blockSignals(false);
@@ -90,7 +90,7 @@ void WaypointViewOnlyView::updateValues()
// 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)
@@ -107,7 +107,7 @@ void WaypointViewOnlyView::updateValues()
// update frame
- m_ui->idLabel->setText(QString("%1").arg(wp->getId()));
+ m_ui->idLabel->setText(QString("%1").arg(wp->sequenceNumber()));
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL:
@@ -142,10 +142,10 @@ void WaypointViewOnlyView::updateValues()
}
}
- if (m_ui->current->isChecked() != wp->getCurrent())
+ if (m_ui->current->isChecked() != wp->isCurrentItem())
{
m_ui->current->blockSignals(true);
- m_ui->current->setChecked(wp->getCurrent());
+ m_ui->current->setChecked(wp->isCurrentItem());
m_ui->current->blockSignals(false);
}
if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
@@ -166,11 +166,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam1()>0)
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (lat %1o,lon %2o,alt %3); yaw: %4; rad: %5").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o,lon %2o,alt %3); yaw: %4; rad: %5").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
}
break;
}
@@ -179,11 +179,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam1()>0)
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and wait there for %4 sec; yaw: %5; rad: %6").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f',2).arg(wp->getParam1()).arg(wp->getParam4()).arg(wp->getParam2()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3); yaw: %4; rad: %5").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3); yaw: %4; rad: %5").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()).arg(wp->getParam2()));
}
break;
}
@@ -199,11 +199,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there indefinitely (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there indefinitely (clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam3()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()));
}
break;
}
@@ -212,11 +212,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there indefinitely (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there indefinitely (clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f',2).arg(wp->getParam3()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()));
}
break;
}
@@ -232,11 +232,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5 turns (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5 turns (clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
@@ -245,11 +245,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5 turns (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5 turns (clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
@@ -265,11 +265,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5s (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5s (clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (lat %1o, lon %2o, alt %3) and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
@@ -278,11 +278,11 @@ void WaypointViewOnlyView::updateValues()
{
if (wp->getParam3()>=0)
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5s (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5s (clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
- m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
+ m_ui->displayBar->setText(QString("Go to (%1, %2, %3) and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
@@ -301,13 +301,13 @@ void WaypointViewOnlyView::updateValues()
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
- m_ui->displayBar->setText(QString("LAND. Go to (lat %1o, lon %2o, alt %3) and descent; yaw: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
+ m_ui->displayBar->setText(QString("LAND. Go to (lat %1o, lon %2o, alt %3) and descent; yaw: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()));
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
- m_ui->displayBar->setText(QString("LAND. Go to (%1, %2, %3) and descent; yaw: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
+ m_ui->displayBar->setText(QString("LAND. Go to (%1, %2, %3) and descent; yaw: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()));
break;
}
} //end Frame switch
@@ -320,13 +320,13 @@ void WaypointViewOnlyView::updateValues()
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
- m_ui->displayBar->setText(QString("TAKEOFF. Go to (lat %1o, lon %2o, alt %3); yaw: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
+ m_ui->displayBar->setText(QString("TAKEOFF. Go to (lat %1o, lon %2o, alt %3); yaw: %4").arg(wp->x(),0, 'f', 7).arg(wp->y(),0, 'f', 7).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()));
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
- m_ui->displayBar->setText(QString("TAKEOFF. Go to (%1, %2, %3); yaw: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam4()));
+ m_ui->displayBar->setText(QString("TAKEOFF. Go to (%1, %2, %3); yaw: %4").arg(wp->x(),0, 'f', 2).arg(wp->y(),0, 'f', 2).arg(wp->z(),0, 'f', 2).arg(wp->getParam4()));
break;
}
} //end Frame switch
diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc
index d331fcac43f73725c169417f6efa1cb1fc0b0fc1..58659c175cefb10dce7b3a925f7d58e755b1b113 100644
--- a/src/ui/map/QGCMapWidget.cc
+++ b/src/ui/map/QGCMapWidget.cc
@@ -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);
}
diff --git a/src/ui/map/Waypoint2DIcon.cc b/src/ui/map/Waypoint2DIcon.cc
index 5d416597f71b5ccff8696a440913115520b1565b..29f6809f644c091b247eaa4b798e9f39a7ce155a 100644
--- a/src/ui/map/Waypoint2DIcon.cc
+++ b/src/ui/map/Waypoint2DIcon.cc
@@ -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();
diff --git a/src/ui/map/Waypoint2DIcon.h b/src/ui/map/Waypoint2DIcon.h
index 66f2f2b3336045982eec7e2a5d6e71d28ffca6dc..8d23fc3b887399eb361a8a5abed0cc30c90ed7a8 100644
--- a/src/ui/map/Waypoint2DIcon.h
+++ b/src/ui/map/Waypoint2DIcon.h
@@ -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);
/**
*