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 += \
src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/QGC.h \
src/QGCApplication.h \
src/QGCComboBox.h \
......@@ -392,6 +393,7 @@ SOURCES += \
src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/QGC.cc \
src/QGCApplication.cc \
src/QGCComboBox.cc \
......@@ -508,6 +510,7 @@ HEADERS += \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \
src/MissionManager/MissionManagerTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/qgcunittest/GeoTest.h \
src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \
......@@ -531,6 +534,7 @@ SOURCES += \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \
src/MissionManager/MissionManagerTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/qgcunittest/GeoTest.cc \
src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \
......
......@@ -89,7 +89,7 @@ FlightMap {
// Add the mission items to the map
MissionItemView {
model: _mainIsMap ? _missionController.missionItems : 0
model: _mainIsMap ? _missionController.visualItems : 0
}
// Add lines between waypoints
......
......@@ -42,8 +42,11 @@ MapQuickItem {
sourceItem:
MissionItemIndexLabel {
id: _label
isCurrentItem: missionItem.isCurrentItem
label: missionItem.sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
isCurrentItem: _isCurrentItem
label: _sequenceNumber == 0 ? "H" : missionItem.sequenceNumber
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
QGCView {
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
topDialogMargin: height - mainWindow.availableHeight
......@@ -60,13 +60,11 @@ QGCView {
readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
property var _missionItems: controller.missionItems
property var _visualItems: controller.visualItems
property var _currentMissionItem
property bool _firstVehiclePosition: true
property var activeVehiclePosition: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
onActiveVehiclePositionChanged: updateMapToVehiclePosition()
Connections {
......@@ -119,19 +117,19 @@ QGCView {
/// Fix the map viewport to the current mission items.
function fitViewportToMissionItems() {
if (_missionItems.count == 1) {
editorMap.center = _missionItems.get(0).coordinate
if (_visualItems.count == 1) {
editorMap.center = _visualItems.get(0).coordinate
} else {
var missionItem = _missionItems.get(0)
var missionItem = _visualItems.get(0)
var north = normalizeLat(missionItem.coordinate.latitude)
var south = north
var east = normalizeLon(missionItem.coordinate.longitude)
var west = east
for (var i=1; i<_missionItems.count; i++) {
missionItem = _missionItems.get(i)
for (var i=1; i<_visualItems.count; i++) {
missionItem = _visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.standaloneCoordinate) {
if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude)
......@@ -161,7 +159,7 @@ QGCView {
onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
*/
onMissionItemsChanged: itemDragger.clearItem()
onVisualItemsChanged: itemDragger.clearItem()
onNewItemsFromVehicle: fitViewportToMissionItems()
}
......@@ -177,12 +175,12 @@ QGCView {
function setCurrentItem(index) {
_currentMissionItem = undefined
for (var i=0; i<_missionItems.count; i++) {
for (var i=0; i<_visualItems.count; i++) {
if (i == index) {
_currentMissionItem = _missionItems.get(i)
_currentMissionItem = _visualItems.get(i)
_currentMissionItem.isCurrentItem = true
} else {
_missionItems.get(i).isCurrentItem = false
_visualItems.get(i).isCurrentItem = false
}
}
}
......@@ -266,7 +264,7 @@ QGCView {
QGCComboBox {
id: toCombo
model: _missionItems.count
model: _visualItems.count
currentIndex: _moveDialogMissionItemIndex
}
}
......@@ -308,7 +306,7 @@ QGCView {
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (addMissionItemsButton.checked) {
var index = controller.insertSimpleMissionItem(coordinate, controller.missionItems.count)
var index = controller.insertSimpleMissionItem(coordinate, controller.visualItems.count)
setCurrentItem(index)
} else {
editorMap.mapClicked(coordinate)
......@@ -368,7 +366,7 @@ QGCView {
// Add the simple mission items to the map
MapItemView {
model: controller.missionItems
model: controller.visualItems
delegate: missionItemComponent
}
......@@ -399,8 +397,8 @@ QGCView {
Connections {
target: object
onIsCurrentItemChanged: updateItemIndicator()
onCommandChanged: updateItemIndicator()
onIsCurrentItemChanged: updateItemIndicator()
onSpecifiesCoordinateChanged: updateItemIndicator()
}
// These are the non-coordinate child mission items attached to this item
......@@ -425,7 +423,7 @@ QGCView {
// Add the complex mission items to the map
MapItemView {
model: controller.complexMissionItems
model: controller.complexVisualItems
delegate: polygonItemComponent
}
......@@ -480,10 +478,10 @@ QGCView {
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
height: Math.min(contentHeight, parent.height)
height: parent.height
spacing: _margin / 2
orientation: ListView.Vertical
model: controller.missionItems
model: controller.visualItems
cacheBuffer: height * 2
delegate: MissionItemEditor {
......@@ -504,7 +502,7 @@ QGCView {
setCurrentItem(i)
}
onMoveHomeToMapCenter: controller.missionItems.get(0).coordinate = editorMap.center
onMoveHomeToMapCenter: controller.visualItems.get(0).coordinate = editorMap.center
}
} // ListView
} // Item - Mission Item editor
......@@ -551,7 +549,7 @@ QGCView {
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.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)
checked = false
}
......@@ -565,8 +563,8 @@ QGCView {
exclusiveGroup: _dropButtonsExclusiveGroup
z: QGroundControl.zOrderWidgets
dropDownComponent: syncDropDownComponent
enabled: !_syncInProgress
rotateImage: _syncInProgress
enabled: !controller.syncInProgress
rotateImage: controller.syncInProgress
}
DropButton {
......@@ -589,7 +587,7 @@ QGCView {
onClicked: {
centerMapButton.hideDropDown()
editorMap.center = controller.missionItems.get(0).coordinate
editorMap.center = controller.visualItems.get(0).coordinate
}
}
......@@ -688,7 +686,7 @@ QGCView {
anchors.bottom: parent.bottom
z: QGroundControl.zOrderTopMost
currentMissionItem: _currentMissionItem
missionItems: controller.missionItems
missionItems: controller.visualItems
expandedWidth: missionItemEditor.x - (ScreenTools.defaultFontPixelWidth * 2)
}
} // FlightMap
......@@ -758,7 +756,7 @@ QGCView {
QGCButton {
text: "Send to vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -768,7 +766,7 @@ QGCView {
QGCButton {
text: "Load from vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -786,6 +784,7 @@ QGCView {
QGCButton {
text: "Save to file..."
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......@@ -795,6 +794,7 @@ QGCView {
QGCButton {
text: "Load from file..."
enabled: !controller.syncInProgress
onClicked: {
syncButton.hideDropDown()
......
......@@ -114,7 +114,7 @@ Rectangle {
Item {
height: graphRow.height
width: ScreenTools.smallFontPixelWidth * 2
visible: object.specifiesCoordinate && !object.standaloneCoordinate
visible: object.specifiesCoordinate && !object.isStandaloneCoordinate
property real availableHeight: height - ScreenTools.smallFontPixelHeight - indicator.height
......
......@@ -23,43 +23,19 @@ This file is part of the QGROUNDCONTROL project
#include "ComplexMissionItem.h"
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent)
: MissionItem(vehicle, parent)
{
}
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)
: VisualMissionItem(vehicle, parent)
, _dirty(false)
{
}
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)
{
return _polygonPath;
......@@ -85,3 +61,33 @@ void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate)
_polygonPath << QVariant::fromValue(coordinate);
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 @@
#ifndef ComplexMissionItem_H
#define ComplexMissionItem_H
#include "VisualMissionItem.h"
#include "MissionItem.h"
class ComplexMissionItem : public MissionItem
class ComplexMissionItem : public VisualMissionItem
{
Q_OBJECT
public:
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);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_INVOKABLE void clearPolygon(void);
......@@ -59,15 +42,38 @@ public:
QVariantList polygonPath(void);
// Overrides from MissionItem base class
bool simpleItem (void) const final { return false; }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
const QList<MissionItem*>& missionItems(void) { return _missionItems; }
/// @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:
void polygonPathChanged(void);
private:
QVariantList _polygonPath;
bool _dirty;
QVariantList _polygonPath;
QList<MissionItem*> _missionItems;
QGeoCoordinate _coordinate;
};
#endif
......@@ -95,7 +95,7 @@ public:
Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT)
Q_PROPERTY(QString friendlyName READ friendlyName 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)
MavlinkQmlSingleton::Qml_MAV_CMD qmlCommand(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; }
......@@ -106,7 +106,7 @@ public:
bool friendlyEdit (void) const { return _friendlyEdit; }
QString friendlyName (void) const { return _friendlyName; }
QString rawName (void) const { return _rawName; }
bool standaloneCoordinate(void) const { return _standaloneCoordinate; }
bool isStandaloneCoordinate(void) const { return _standaloneCoordinate; }
bool specifiesCoordinate (void) const { return _specifiesCoordinate; }
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
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
#include "MavlinkQmlSingleton.h"
#include "MissionItem.h"
#include "VisualMissionItem.h"
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
......@@ -42,11 +42,11 @@ public:
MissionController(QObject* parent = NULL);
~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
Q_PROPERTY(QmlObjectListModel* complexVisualItems READ complexVisualItems NOTIFY complexVisualItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged)
Q_INVOKABLE void start(bool editMode);
Q_INVOKABLE void getMissionItems(void);
......@@ -67,16 +67,17 @@ public:
// Property accessors
QmlObjectListModel* missionItems(void);
QmlObjectListModel* complexMissionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* complexVisualItems (void) { return _complexItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
bool syncInProgress(void);
signals:
void missionItemsChanged(void);
void complexMissionItemsChanged(void);
void visualItemsChanged(void);
void complexVisualItemsChanged(void);
void waypointLinesChanged(void);
void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void);
......@@ -85,41 +86,40 @@ signals:
private slots:
void _newMissionItemsAvailableFromVehicle();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemFrameChanged(int frame);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _itemCommandChanged(void);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
void _dirtyChanged(bool dirty);
void _inProgressChanged(bool inProgress);
void _currentMissionItemChanged(int sequenceNumber);
void _recalcWaypointLines(void);
private:
void _recalcSequence(void);
void _recalcWaypointLines(void);
void _recalcChildItems(void);
void _recalcAll(void);
void _initAllMissionItems(void);
void _deinitAllMissionItems(void);
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _initAllVisualItems(void);
void _deinitAllVisualItems(void);
void _initVisualItem(VisualMissionItem* item);
void _deinitVisualItem(VisualMissionItem* item);
void _autoSyncSend(void);
void _setupActiveVehicle(Vehicle* activeVehicle, bool forceLoadFromVehicle);
void _calcPrevWaypointValues(double homeAlt, MissionItem* currentItem, MissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
void _calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
bool _findLastAltitude(double* lastAltitude);
bool _findLastAcceptanceRadius(double* lastAcceptanceRadius);
void _addPlannedHomePosition(QmlObjectListModel* missionItems, bool addToCenter);
void _addPlannedHomePosition(QmlObjectListModel* visualItems, bool addToCenter);
double _normalizeLat(double lat);
double _normalizeLon(double lon);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* missionItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* missionItems, QString& errorString);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
void _loadMissionFromFile(const QString& file);
void _saveMissionToFile(const QString& file);
private:
bool _editMode;
QmlObjectListModel* _missionItems;
QmlObjectListModel* _complexMissionItems;
QmlObjectListModel* _visualItems;
QmlObjectListModel* _complexItems;
QmlObjectListModel _waypointLines;
Vehicle* _activeVehicle;
bool _autoSync;
......
......@@ -63,7 +63,7 @@ void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareTy
}
QVERIFY(!_missionManager->inProgress());
QCOMPARE(_missionManager->missionItems()->count(), 0);
QCOMPARE(_missionManager->missionItems().count(), 0);
_multiSpyMissionManager->clearAllSignals();
}
......
......@@ -24,6 +24,7 @@
#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
MissionControllerTest::MissionControllerTest(void)
: _multiSpyMissionController(NULL)
......@@ -62,7 +63,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
_rgMissionItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
// MissionController signals
_rgMissionControllerSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
_rgMissionControllerSignals[visualItemsChangedSignalIndex] = SIGNAL(visualItemsChanged());
_rgMissionControllerSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
if (!_missionController) {
......@@ -80,17 +81,17 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
}
// All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
_multiSpyMissionController->clearAllSignals();
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
// Empty vehicle only has home position
QCOMPARE(missionItems->count(), 1);
QCOMPARE(visualItems->count(), 1);
// Home position should be in first slot, but not yet valid
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
QVERIFY(homeItem);
QCOMPARE(homeItem->homePosition(), true);
......@@ -113,9 +114,9 @@ void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
// FYI: A significant amount of empty vehicle testing is in _initForFirmwareType since that
// sets up an empty vehicle
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
QVERIFY(homeItem);
_setupMissionItemSignals(homeItem);
......@@ -137,17 +138,17 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->insertSimpleMissionItem(coordinate, _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(coordinate, _missionController->visualItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
QCOMPARE(missionItems->count(), 2);
QCOMPARE(visualItems->count(), 2);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
SimpleMissionItem* homeItem = qobject_cast<SimpleMissionItem*>(visualItems->get(0));
SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(1));
QVERIFY(homeItem);
QVERIFY(item);
......@@ -182,13 +183,13 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
// Make sure our offline mission items are still there
QCOMPARE(_missionController->missionItems()->count(), 2);
QCOMPARE(_missionController->visualItems()->count(), 2);
}
void MissionControllerTest::_testOfflineToOnlineAPM(void)
......@@ -201,7 +202,7 @@ void MissionControllerTest::_testOfflineToOnlinePX4(void)
_testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
void MissionControllerTest::_setupMissionItemSignals(MissionItem* item)
void MissionControllerTest::_setupMissionItemSignals(SimpleMissionItem* item)
{
delete _multiSpyMissionItem;
......
......@@ -30,6 +30,7 @@
#include "MultiSignalSpy.h"
#include "MissionControllerManagerTest.h"
#include "MissionController.h"
#include "SimpleMissionItem.h"
#include <QGeoCoordinate>
......@@ -55,7 +56,7 @@ private:
void _testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType);
void _testAddWaypointWorker(MAV_AUTOPILOT firmwareType);
void _testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType);
void _setupMissionItemSignals(MissionItem* item);
void _setupMissionItemSignals(SimpleMissionItem* item);
// MissiomItems signals
......@@ -72,13 +73,13 @@ private:
// MissionController signals
enum {
missionItemsChangedSignalIndex = 0,
visualItemsChangedSignalIndex = 0,
waypointLinesChangedSignalIndex,
missionControllerMaxSignalIndex
};
enum {
missionItemsChangedSignalMask = 1 << missionItemsChangedSignalIndex,
visualItemsChangedSignalMask = 1 << visualItemsChangedSignalIndex,
waypointLinesChangedSignalMask = 1 << waypointLinesChangedSignalIndex,
};
......
This diff is collapsed.