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; }
......
......@@ -46,8 +46,8 @@ const char* MissionController::_jsonPlannedHomePositionKey = "plannedHomePosi
MissionController::MissionController(QObject *parent)
: QObject(parent)
, _editMode(false)
, _missionItems(NULL)
, _complexMissionItems(NULL)
, _visualItems(NULL)
, _complexItems(NULL)
, _activeVehicle(NULL)
, _autoSync(false)
, _firstItemsFromVehicle(false)
......@@ -74,9 +74,9 @@ void MissionController::start(bool editMode)
_activeVehicleChanged(multiVehicleMgr->activeVehicle());
// We start with an empty mission
_missionItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_missionItems, false /* addToCenter */);
_initAllMissionItems();
_visualItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_visualItems, false /* addToCenter */);
_initAllVisualItems();
}
// Called when new mission items have completed downloading from Vehicle
......@@ -84,25 +84,33 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void)
{
qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";
if (!_editMode || _missionItemsRequested || _missionItems->count() == 1) {
if (!_editMode || _missionItemsRequested || _visualItems->count() == 1) {
// Fly Mode:
// - Always accepts new items fromthe vehicle so Fly view is kept up to date
// Edit Mode:
// - Either a load from vehicle was manually requested or
// - The initial automatic load from a vehicle completed and the current editor it empty
_deinitAllMissionItems();
_missionItems->deleteLater();
_missionItems = _activeVehicle->missionManager()->copyMissionItems();
qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
const QList<MissionItem*>& newMissionItems = _activeVehicle->missionManager()->missionItems();
if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _missionItems->count() == 0) {
_addPlannedHomePosition(_missionItems,true /* addToCenter */);
qCDebug(MissionControllerLog) << "loading from vehicle: count"<< _visualItems->count();
foreach(const MissionItem* missionItem, newMissionItems) {
newControllerMissionItems->append(new SimpleMissionItem(_activeVehicle, *missionItem, this));
}
_deinitAllVisualItems();
_visualItems->deleteListAndContents();
_visualItems = newControllerMissionItems;
if (!_activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
_addPlannedHomePosition(_visualItems,true /* addToCenter */);
}
_missionItemsRequested = false;
_initAllMissionItems();
_initAllVisualItems();
emit newItemsFromVehicle();
}
}
......@@ -119,22 +127,39 @@ void MissionController::getMissionItems(void)
void MissionController::sendMissionItems(void)
{
Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
if (_activeVehicle) {
// Convert to MissionItems so we can send to vehicle
if (activeVehicle) {
activeVehicle->missionManager()->writeMissionItems(*_missionItems);
_missionItems->setDirty(false);
QList<MissionItem*> missionItems;
int sequenceNumber = 0;
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
if (visualItem->isSimpleItem()) {
MissionItem& missionItem = qobject_cast<SimpleMissionItem*>(visualItem)->missionItem();
missionItem.setSequenceNumber(sequenceNumber++);
missionItems.append(&missionItem);
} else {
foreach (MissionItem* missionItem, qobject_cast<ComplexMissionItem*>(visualItem)->missionItems()) {
missionItem->setSequenceNumber(sequenceNumber++);
missionItems.append(missionItem);
}
}
}
_activeVehicle->missionManager()->writeMissionItems(missionItems);
_visualItems->setDirty(false);
}
}
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
{
MissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_visualItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initMissionItem(newItem);
if (_missionItems->count() == 1) {
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
if (_visualItems->count() == 1) {
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
}
newItem->setDefaultsForCommand();
......@@ -142,64 +167,71 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
double lastValue;
if (_findLastAcceptanceRadius(&lastValue)) {
newItem->setParam2(lastValue);
newItem->missionItem().setParam2(lastValue);
}
if (_findLastAltitude(&lastValue)) {
newItem->setParam7(lastValue);
newItem->missionItem().setParam7(lastValue);
}
}
_missionItems->insert(i, newItem);
_visualItems->insert(i, newItem);
_recalcAll();
return _missionItems->count() - 1;
return _visualItems->count() - 1;
}
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
ComplexMissionItem * newItem = new ComplexMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_visualItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initMissionItem(newItem);
_initVisualItem(newItem);
_missionItems->insert(i, newItem);
_complexMissionItems->append(newItem);
_visualItems->insert(i, newItem);
_complexItems->append(newItem);
_recalcAll();
return _missionItems->count() - 1;
return _visualItems->count() - 1;
}
void MissionController::removeMissionItem(int index)
{
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
_deinitMissionItem(item);
_deinitVisualItem(item);
if (!item->isSimpleItem()) {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
if (complexItem) {
complexItem->deleteLater();
} else {
qWarning() << "Complex item missing";
}
}
item->deleteLater();
_recalcAll();
// Set the new current item
if (index >= _missionItems->count()) {
if (index >= _visualItems->count()) {
index--;
}
for (int i=0; i<_missionItems->count(); i++) {
MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
for (int i=0; i<_visualItems->count(); i++) {
MissionItem* item = qobject_cast<MissionItem*>(_visualItems->get(i));
item->setIsCurrentItem(i == index);
}
_missionItems->setDirty(true);
_visualItems->setDirty(true);
}
void MissionController::removeAllMissionItems(void)
{
if (_missionItems) {
QmlObjectListModel* oldItems = _missionItems;
_missionItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_missionItems, false /* addToCenter */);
_initAllMissionItems();
oldItems->deleteLater();
if (_visualItems) {
_deinitAllVisualItems();
_visualItems->deleteListAndContents();
_visualItems = new QmlObjectListModel(this);
_addPlannedHomePosition(_visualItems, false /* addToCenter */);
_initAllVisualItems();
}
}
......@@ -237,7 +269,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
return false;
}
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(itemValue.toObject(), errorString)) {
missionItems->append(item);
} else {
......@@ -247,7 +279,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
}
if (json.contains(_jsonPlannedHomePositionKey)) {
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), errorString)) {
missionItems->insert(0, item);
......@@ -261,7 +293,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
return true;
}
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* missionItems, QString& errorString)
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
{
bool addPlannedHomePosition = false;
......@@ -282,10 +314,10 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
if (versionOk) {
while (!stream.atEnd()) {
MissionItem* item = new SimpleMissionItem(_activeVehicle, this);
SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);
if (item->load(stream)) {
missionItems->append(item);
visualItems->append(item);
} else {
errorString = QStringLiteral("The mission file is corrupted.");
return false;
......@@ -296,15 +328,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
return false;
}