Commit 32b8a549 authored by Don Gagne's avatar Don Gagne

Simple/Complex item rearchitecture

Plus new unit tests
parent e27ab01d
...@@ -263,6 +263,7 @@ HEADERS += \ ...@@ -263,6 +263,7 @@ HEADERS += \
src/MissionManager/MissionManager.h \ src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \ src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \ src/MissionManager/SimpleMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/QGC.h \ src/QGC.h \
src/QGCApplication.h \ src/QGCApplication.h \
src/QGCComboBox.h \ src/QGCComboBox.h \
...@@ -392,6 +393,7 @@ SOURCES += \ ...@@ -392,6 +393,7 @@ SOURCES += \
src/MissionManager/MissionManager.cc \ src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \ src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \ src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/QGC.cc \ src/QGC.cc \
src/QGCApplication.cc \ src/QGCApplication.cc \
src/QGCComboBox.cc \ src/QGCComboBox.cc \
...@@ -508,6 +510,7 @@ HEADERS += \ ...@@ -508,6 +510,7 @@ HEADERS += \
src/MissionManager/MissionControllerManagerTest.h \ src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \ src/MissionManager/MissionItemTest.h \
src/MissionManager/MissionManagerTest.h \ src/MissionManager/MissionManagerTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/qgcunittest/GeoTest.h \ src/qgcunittest/GeoTest.h \
src/qgcunittest/FileDialogTest.h \ src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \ src/qgcunittest/FileManagerTest.h \
...@@ -531,6 +534,7 @@ SOURCES += \ ...@@ -531,6 +534,7 @@ SOURCES += \
src/MissionManager/MissionControllerManagerTest.cc \ src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \ src/MissionManager/MissionItemTest.cc \
src/MissionManager/MissionManagerTest.cc \ src/MissionManager/MissionManagerTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/qgcunittest/GeoTest.cc \ src/qgcunittest/GeoTest.cc \
src/qgcunittest/FileDialogTest.cc \ src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \ src/qgcunittest/FileManagerTest.cc \
......
...@@ -89,7 +89,7 @@ FlightMap { ...@@ -89,7 +89,7 @@ FlightMap {
// Add the mission items to the map // Add the mission items to the map
MissionItemView { MissionItemView {
model: _mainIsMap ? _missionController.missionItems : 0 model: _mainIsMap ? _missionController.visualItems : 0
} }
// Add lines between waypoints // Add lines between waypoints
......
...@@ -42,8 +42,11 @@ MapQuickItem { ...@@ -42,8 +42,11 @@ MapQuickItem {
sourceItem: sourceItem:
MissionItemIndexLabel { MissionItemIndexLabel {
id: _label id: _label
isCurrentItem: missionItem.isCurrentItem isCurrentItem: _isCurrentItem
label: missionItem.sequenceNumber == 0 ? "H" : missionItem.sequenceNumber label: _sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
onClicked: _item.clicked() onClicked: _item.clicked()
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
property bool _sequenceNumber: missionItem ? missionItem.sequenceNumber : 0
} }
} }
...@@ -40,7 +40,7 @@ import QGroundControl.Controllers 1.0 ...@@ -40,7 +40,7 @@ import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: _root id: _root
property bool syncNeeded: controller.missionItems.dirty // Unsaved changes, visible to parent container property bool syncNeeded: controller.visualItems.dirty // Unsaved changes, visible to parent container
viewPanel: panel viewPanel: panel
topDialogMargin: height - mainWindow.availableHeight topDialogMargin: height - mainWindow.availableHeight
...@@ -60,13 +60,11 @@ QGCView { ...@@ -60,13 +60,11 @@ QGCView {
readonly property int _addMissionItemsButtonAutoOffTimeout: 10000 readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276) readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
property var _missionItems: controller.missionItems property var _visualItems: controller.visualItems
property var _currentMissionItem property var _currentMissionItem
property bool _firstVehiclePosition: true property bool _firstVehiclePosition: true
property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
onActiveVehiclePositionChanged: updateMapToVehiclePosition() onActiveVehiclePositionChanged: updateMapToVehiclePosition()
Connections { Connections {
...@@ -119,19 +117,19 @@ QGCView { ...@@ -119,19 +117,19 @@ QGCView {
/// Fix the map viewport to the current mission items. /// Fix the map viewport to the current mission items.
function fitViewportToMissionItems() { function fitViewportToMissionItems() {
if (_missionItems.count == 1) { if (_visualItems.count == 1) {
editorMap.center = _missionItems.get(0).coordinate editorMap.center = _visualItems.get(0).coordinate
} else { } else {
var missionItem = _missionItems.get(0) var missionItem = _visualItems.get(0)
var north = normalizeLat(missionItem.coordinate.latitude) var north = normalizeLat(missionItem.coordinate.latitude)
var south = north var south = north
var east = normalizeLon(missionItem.coordinate.longitude) var east = normalizeLon(missionItem.coordinate.longitude)
var west = east var west = east
for (var i=1; i<_missionItems.count; i++) { for (var i=1; i<_visualItems.count; i++) {
missionItem = _missionItems.get(i) missionItem = _visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.standaloneCoordinate) { if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
var lat = normalizeLat(missionItem.coordinate.latitude) var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude) var lon = normalizeLon(missionItem.coordinate.longitude)
...@@ -161,7 +159,7 @@ QGCView { ...@@ -161,7 +159,7 @@ QGCView {
onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync) onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
*/ */
onMissionItemsChanged: itemDragger.clearItem() onVisualItemsChanged: itemDragger.clearItem()
onNewItemsFromVehicle: fitViewportToMissionItems() onNewItemsFromVehicle: fitViewportToMissionItems()
} }
...@@ -177,12 +175,12 @@ QGCView { ...@@ -177,12 +175,12 @@ QGCView {
function setCurrentItem(index) { function setCurrentItem(index) {
_currentMissionItem = undefined _currentMissionItem = undefined
for (var i=0; i<_missionItems.count; i++) { for (var i=0; i<_visualItems.count; i++) {
if (i == index) { if (i == index) {
_currentMissionItem = _missionItems.get(i) _currentMissionItem = _visualItems.get(i)
_currentMissionItem.isCurrentItem = true _currentMissionItem.isCurrentItem = true
} else { } else {
_missionItems.get(i).isCurrentItem = false _visualItems.get(i).isCurrentItem = false
} }
} }
} }
...@@ -266,7 +264,7 @@ QGCView { ...@@ -266,7 +264,7 @@ QGCView {
QGCComboBox { QGCComboBox {
id: toCombo id: toCombo
model: _missionItems.count model: _visualItems.count
currentIndex: _moveDialogMissionItemIndex currentIndex: _moveDialogMissionItemIndex
} }
} }
...@@ -308,7 +306,7 @@ QGCView { ...@@ -308,7 +306,7 @@ QGCView {
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (addMissionItemsButton.checked) { if (addMissionItemsButton.checked) {
var index = controller.insertSimpleMissionItem(coordinate, controller.missionItems.count) var index = controller.insertSimpleMissionItem(coordinate, controller.visualItems.count)
setCurrentItem(index) setCurrentItem(index)
} else { } else {
editorMap.mapClicked(coordinate) editorMap.mapClicked(coordinate)
...@@ -368,7 +366,7 @@ QGCView { ...@@ -368,7 +366,7 @@ QGCView {
// Add the simple mission items to the map // Add the simple mission items to the map
MapItemView { MapItemView {
model: controller.missionItems model: controller.visualItems
delegate: missionItemComponent delegate: missionItemComponent
} }
...@@ -399,8 +397,8 @@ QGCView { ...@@ -399,8 +397,8 @@ QGCView {
Connections { Connections {
target: object target: object
onIsCurrentItemChanged: updateItemIndicator() onIsCurrentItemChanged: updateItemIndicator()
onCommandChanged: updateItemIndicator() onSpecifiesCoordinateChanged: updateItemIndicator()
} }
// These are the non-coordinate child mission items attached to this item // These are the non-coordinate child mission items attached to this item
...@@ -425,7 +423,7 @@ QGCView { ...@@ -425,7 +423,7 @@ QGCView {
// Add the complex mission items to the map // Add the complex mission items to the map
MapItemView { MapItemView {
model: controller.complexMissionItems model: controller.complexVisualItems
delegate: polygonItemComponent delegate: polygonItemComponent
} }
...@@ -480,10 +478,10 @@ QGCView { ...@@ -480,10 +478,10 @@ QGCView {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: parent.top anchors.top: parent.top
height: Math.min(contentHeight, parent.height) height: parent.height
spacing: _margin / 2 spacing: _margin / 2
orientation: ListView.Vertical orientation: ListView.Vertical
model: controller.missionItems model: controller.visualItems
cacheBuffer: height * 2 cacheBuffer: height * 2
delegate: MissionItemEditor { delegate: MissionItemEditor {
...@@ -504,7 +502,7 @@ QGCView { ...@@ -504,7 +502,7 @@ QGCView {
setCurrentItem(i) setCurrentItem(i)
} }
onMoveHomeToMapCenter: controller.missionItems.get(0).coordinate = editorMap.center onMoveHomeToMapCenter: controller.visualItems.get(0).coordinate = editorMap.center
} }
} // ListView } // ListView
} // Item - Mission Item editor } // Item - Mission Item editor
...@@ -551,7 +549,7 @@ QGCView { ...@@ -551,7 +549,7 @@ QGCView {
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.insertComplexMissionItem(coordinate, controller.missionItems.count) var index = controller.insertComplexMissionItem(coordinate, controller.visualItems.count)
setCurrentItem(index) setCurrentItem(index)
checked = false checked = false
} }
...@@ -565,8 +563,8 @@ QGCView { ...@@ -565,8 +563,8 @@ QGCView {
exclusiveGroup: _dropButtonsExclusiveGroup exclusiveGroup: _dropButtonsExclusiveGroup
z: QGroundControl.zOrderWidgets z: QGroundControl.zOrderWidgets
dropDownComponent: syncDropDownComponent dropDownComponent: syncDropDownComponent
enabled: !_syncInProgress enabled: !controller.syncInProgress
rotateImage: _syncInProgress rotateImage: controller.syncInProgress
} }
DropButton { DropButton {
...@@ -589,7 +587,7 @@ QGCView { ...@@ -589,7 +587,7 @@ QGCView {
onClicked: { onClicked: {
centerMapButton.hideDropDown() centerMapButton.hideDropDown()
editorMap.center = controller.missionItems.get(0).coordinate editorMap.center = controller.visualItems.get(0).coordinate
} }
} }
...@@ -688,7 +686,7 @@ QGCView { ...@@ -688,7 +686,7 @@ QGCView {
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
z: QGroundControl.zOrderTopMost z: QGroundControl.zOrderTopMost
currentMissionItem: _currentMissionItem currentMissionItem: _currentMissionItem
missionItems: controller.missionItems missionItems: controller.visualItems
expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2) expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2)
} }
} // FlightMap } // FlightMap
...@@ -758,7 +756,7 @@ QGCView { ...@@ -758,7 +756,7 @@ QGCView {
QGCButton { QGCButton {
text: "Send to vehicle" text: "Send to vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress enabled: !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
...@@ -768,7 +766,7 @@ QGCView { ...@@ -768,7 +766,7 @@ QGCView {
QGCButton { QGCButton {
text: "Load from vehicle" text: "Load from vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress enabled: !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
...@@ -786,6 +784,7 @@ QGCView { ...@@ -786,6 +784,7 @@ QGCView {
QGCButton { QGCButton {
text: "Save to file..." text: "Save to file..."
enabled: !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
...@@ -795,6 +794,7 @@ QGCView { ...@@ -795,6 +794,7 @@ QGCView {
QGCButton { QGCButton {
text: "Load from file..." text: "Load from file..."
enabled: !controller.syncInProgress
onClicked: { onClicked: {
syncButton.hideDropDown() syncButton.hideDropDown()
......
...@@ -114,7 +114,7 @@ Rectangle { ...@@ -114,7 +114,7 @@ Rectangle {
Item { Item {
height: graphRow.height height: graphRow.height
width: ScreenTools.smallFontPixelWidth * 2 width: ScreenTools.smallFontPixelWidth * 2
visible: object.specifiesCoordinate && !object.standaloneCoordinate visible: object.specifiesCoordinate && !object.isStandaloneCoordinate
property real availableHeight: height - ScreenTools.smallFontPixelHeight - indicator.height property real availableHeight: height - ScreenTools.smallFontPixelHeight - indicator.height
......
...@@ -23,43 +23,19 @@ This file is part of the QGROUNDCONTROL project ...@@ -23,43 +23,19 @@ This file is part of the QGROUNDCONTROL project
#include "ComplexMissionItem.h" #include "ComplexMissionItem.h"
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent) ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent) : VisualMissionItem(vehicle, parent)
{ , _dirty(false)
}
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent)
: MissionItem(vehicle, sequenceNumber, command, frame, param1, param2, param3, param4, param5, param6, param7, autoContinue, isCurrentItem, parent)
{ {
} }
ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent) ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent)
: MissionItem(other, parent) : VisualMissionItem(other, parent)
, _dirty(false)
{ {
} }
const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem& other)
{
static_cast<MissionItem&>(*this) = other;
return *this;
}
QVariantList ComplexMissionItem::polygonPath(void) QVariantList ComplexMissionItem::polygonPath(void)
{ {
return _polygonPath; return _polygonPath;
...@@ -85,3 +61,33 @@ void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate) ...@@ -85,3 +61,33 @@ void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
_polygonPath << QVariant::fromValue(coordinate); _polygonPath << QVariant::fromValue(coordinate);
emit polygonPathChanged(); emit polygonPathChanged();
} }
int ComplexMissionItem::nextSequenceNumber(void) const
{
return _sequenceNumber + _missionItems.count();
}
void ComplexMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
if (_coordinate != coordinate) {
_coordinate = coordinate;
emit coordinateChanged(_coordinate);
}
}
void ComplexMissionItem::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
}
}
bool ComplexMissionItem::save(QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString)
{
Q_UNUSED(missionObject);
Q_UNUSED(missionItems);
errorString = "Complex save NYI";
return false;
}
...@@ -24,34 +24,17 @@ ...@@ -24,34 +24,17 @@
#ifndef ComplexMissionItem_H #ifndef ComplexMissionItem_H
#define ComplexMissionItem_H #define ComplexMissionItem_H
#include "VisualMissionItem.h"
#include "MissionItem.h" #include "MissionItem.h"
class ComplexMissionItem : public MissionItem class ComplexMissionItem : public VisualMissionItem
{ {
Q_OBJECT Q_OBJECT
public: public:
ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL); ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL);
ComplexMissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
double param2,
double param3,
double param4,
double param5,
double param6,
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
ComplexMissionItem(const ComplexMissionItem& other, QObject* parent = NULL); ComplexMissionItem(const ComplexMissionItem& other, QObject* parent = NULL);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged) Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_INVOKABLE void clearPolygon(void); Q_INVOKABLE void clearPolygon(void);
...@@ -59,15 +42,38 @@ public: ...@@ -59,15 +42,38 @@ public:
QVariantList polygonPath(void); QVariantList polygonPath(void);
// Overrides from MissionItem base class const QList<MissionItem*>& missionItems(void) { return _missionItems; }
bool simpleItem (void) const final { return false; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); } /// @return The next sequence number to use after this item. Takes into account child items of the complex item
int nextSequenceNumber(void) const;
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final { return true; }
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _coordinate; }
bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate);
bool save (QJsonObject& missionObject, QJsonArray& missionItems, QString& errorString) final;
signals: signals:
void polygonPathChanged(void); void polygonPathChanged(void);
private: private:
QVariantList _polygonPath; bool _dirty;
QVariantList _polygonPath;
QList<MissionItem*> _missionItems;
QGeoCoordinate _coordinate;
}; };
#endif #endif
...@@ -95,7 +95,7 @@ public: ...@@ -95,7 +95,7 @@ public:
Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT) Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT)
Q_PROPERTY(QString friendlyName READ friendlyName CONSTANT) Q_PROPERTY(QString friendlyName READ friendlyName CONSTANT)
Q_PROPERTY(QString rawName READ rawName CONSTANT) Q_PROPERTY(QString rawName READ rawName CONSTANT)
Q_PROPERTY(bool standaloneCoordinate READ standaloneCoordinate CONSTANT) Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT) Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
MavlinkQmlSingleton::Qml_MAV_CMD qmlCommand(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; } MavlinkQmlSingleton::Qml_MAV_CMD qmlCommand(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; }
...@@ -106,7 +106,7 @@ public: ...@@ -106,7 +106,7 @@ public:
bool friendlyEdit (void) const { return _friendlyEdit; } bool friendlyEdit (void) const { return _friendlyEdit; }
QString friendlyName (void) const { return _friendlyName; } QString friendlyName (void) const { return _friendlyName; }
QString rawName (void) const { return _rawName; } QString rawName (void) const { return _rawName; }
bool standaloneCoordinate(void) const { return _standaloneCoordinate; } bool isStandaloneCoordinate(void) const { return _standaloneCoordinate; }
bool specifiesCoordinate (void) const { return _specifiesCoordinate; } bool specifiesCoordinate (void) const { return _specifiesCoordinate; }
const QMap<int, MavCmdParamInfo*>& paramInfoMap(void) const { return _paramInfoMap; } const QMap<int, MavCmdParamInfo*>& paramInfoMap(void) const { return _paramInfoMap; }
......
This diff is collapsed.
...@@ -30,7 +30,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -30,7 +30,7 @@ This file is part of the QGROUNDCONTROL project
#include "Vehicle.h" #include "Vehicle.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h" #include "MavlinkQmlSingleton.h"
#include "MissionItem.h" #include "VisualMissionItem.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog) Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
...@@ -42,11 +42,11 @@ public: ...@@ -42,11 +42,11 @@ public:
MissionController(QObject* parent = NULL); MissionController(QObject* parent = NULL);
~MissionController(); ~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged) Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged) Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged) Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
Q_INVOKABLE void start(bool editMode); Q_INVOKABLE void start(bool editMode);
Q_INVOKABLE void getMissionItems(void); Q_INVOKABLE void getMissionItems(void);
...@@ -67,16 +67,17 @@ public: ...@@ -67,16 +67,17 @@ public:
// Property accessors // Property accessors
QmlObjectListModel* missionItems(void); QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* complexMissionItems(void); QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines(void) { return &_waypointLines; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
bool autoSync(void) { return _autoSync; } bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync); void setAutoSync(bool autoSync);
bool syncInProgress(void); bool syncInProgress(void);
signals: signals:
void missionItemsChanged(void); void visualItemsChanged(void);
void complexMissionItemsChanged(void); void complexVisualItemsChanged(void);
void waypointLinesChanged(void); void waypointLinesChanged(void);
void autoSyncChanged(bool autoSync); void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void); void newItemsFromVehicle(void);
...@@ -85,41 +86,40 @@ signals: ...@@ -85,41 +86,40 @@ signals:
private slots: private slots:
void _newMissionItemsAvailableFromVehicle(); void _newMissionItemsAvailableFromVehicle();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate); void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemFrameChanged(int frame); void _itemCommandChanged(void);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);