From 5f0128d35c744ee390a6c8a3b455a7859f6b78fb Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Fri, 15 Dec 2017 11:45:31 -0800 Subject: [PATCH] Reduce memory footprint of Plan/Fly mission handling --- src/FlightMap/MapItems/PlanMapItems.qml | 32 +++++--------- src/MissionManager/CameraSectionTest.cc | 27 ++++++++---- src/MissionManager/GeoFenceManager.cc | 5 +-- src/MissionManager/MissionController.cc | 36 ++++++++++++---- src/MissionManager/MissionController.h | 48 +++++++++++---------- src/MissionManager/MissionManager.cc | 5 --- src/MissionManager/PlanManager.cc | 10 +++-- src/MissionManager/PlanManager.h | 1 + src/MissionManager/SectionTest.cc | 4 +- src/MissionManager/SimpleMissionItem.cc | 11 +++-- src/MissionManager/SimpleMissionItem.h | 2 +- src/MissionManager/SimpleMissionItemTest.cc | 4 +- src/MissionManager/SpeedSectionTest.cc | 6 +-- 13 files changed, 107 insertions(+), 84 deletions(-) diff --git a/src/FlightMap/MapItems/PlanMapItems.qml b/src/FlightMap/MapItems/PlanMapItems.qml index 559e2d092..770b40e13 100644 --- a/src/FlightMap/MapItems/PlanMapItems.qml +++ b/src/FlightMap/MapItems/PlanMapItems.qml @@ -15,7 +15,8 @@ import QGroundControl 1.0 import QGroundControl.Controls 1.0 import QGroundControl.FlightMap 1.0 -// Adds visual items associated with the Flight Plan to the map +// Adds visual items associated with the Flight Plan to the map. +// Currently only used by Fly View even though it's called PlanMapItems! Item { id: _root @@ -45,24 +46,15 @@ Item { } } - // Waypoint lines - Instantiator { - model: largeMapView ? _missionController.waypointLines : 0 - - Item { - property var _missionLineViewComponent - - Component.onCompleted: { - _missionLineViewComponent = missionLineViewComponent.createObject(map, {"object": object}) - if (_missionLineViewComponent.status === Component.Error) - console.log(_missionLineViewComponent.errorString()) - map.addMapItem(_missionLineViewComponent) - } + Component.onCompleted: { + _missionLineViewComponent = missionLineViewComponent.createObject(map) + if (_missionLineViewComponent.status === Component.Error) + console.log(_missionLineViewComponent.errorString()) + map.addMapItem(_missionLineViewComponent) + } - Component.onDestruction: { - _missionLineViewComponent.destroy() - } - } + Component.onDestruction: { + _missionLineViewComponent.destroy() } Component { @@ -72,9 +64,7 @@ Item { line.width: 3 line.color: "#be781c" // Hack, can't get palette to work in here z: QGroundControl.zOrderWaypointLines - path: object ? [ object.coordinate1, object.coordinate2] : undefined - - property var object + path: _missionController.waypointPath } } } diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index b93aae5c1..69eb38db7 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -46,12 +46,15 @@ void CameraSectionTest::init(void) QVERIFY(_spySection); _validGimbalItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false), this); _validTimeItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false), this); _validDistanceItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, @@ -62,6 +65,7 @@ void CameraSectionTest::init(void) true, false), this); _validStartVideoItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, // sequence number MAV_CMD_VIDEO_START_CAPTURE, MAV_FRAME_MISSION, @@ -72,15 +76,19 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validStopVideoItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false), this); _validStopDistanceItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false), this); _validStopTimeItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false), this); _validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -91,6 +99,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validCameraVideoModeItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -101,6 +110,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validCameraSurveyPhotoModeItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -111,6 +121,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validTakePhotoItem = new SimpleMissionItem(_offlineVehicle, + true, // editMode MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, @@ -351,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, missionItem); + SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); QVERIFY(item->cameraSection()); QCOMPARE(item->cameraSection()->available(), false); } @@ -622,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Gimbal command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validGimbalItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validGimbalItem->missionItem()); invalidSimpleItem.missionItem().setParam2(10); // roll is not supported visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -712,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) */ // Mode command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validCameraPhotoModeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validCameraPhotoModeItem->missionItem()); invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -751,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) // Image start command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validTimeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem()); invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -792,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validDistanceItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validDistanceItem->missionItem()); invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -877,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) // Start Video command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validStartVideoItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStartVideoItem->missionItem()); invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0) visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -920,7 +931,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validStopVideoItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStopVideoItem->missionItem()); invalidSimpleItem.missionItem().setParam1(10); // must be 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -993,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) // Take Photo command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validTimeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem()); invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); diff --git a/src/MissionManager/GeoFenceManager.cc b/src/MissionManager/GeoFenceManager.cc index 448be9eb0..ce6ce1933 100644 --- a/src/MissionManager/GeoFenceManager.cc +++ b/src/MissionManager/GeoFenceManager.cc @@ -99,11 +99,8 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, fenceItems.append(item); } + // Plan manager takes control of MissionItems, so no need to delete _planManager.writeMissionItems(fenceItems); - - for (int i=0; ideleteLater(); - } } void GeoFenceManager::removeAll(void) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 88d8faae8..8f04b18e9 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -175,7 +175,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque for (; iappend(new SimpleMissionItem(_controllerVehicle, *missionItem, this)); + newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _editMode, *missionItem, this)); } _deinitAllVisualItems(); @@ -313,11 +313,8 @@ void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle); + // PlanManager takes control of MissionItems so no need to delete vehicle->missionManager()->writeMissionItems(rgMissionItems); - - for (int i=0; ideleteLater(); - } } } @@ -1021,6 +1018,7 @@ void MissionController::_recalcWaypointLines(void) CoordVectHashTable old_table = _linesTable; _linesTable.clear(); _waypointLines.clear(); + _waypointPath.clear(); bool linkEndToHome; SimpleMissionItem* lastItem = _visualItems->value(_visualItems->count() - 1); @@ -1042,22 +1040,33 @@ void MissionController::_recalcWaypointLines(void) qobject_cast(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || qobject_cast(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) { linkStartToHome = true; + if (!_editMode) { + _waypointPath.append(QVariant::fromValue(lastCoordinateItem->coordinate())); + } } if (item->specifiesCoordinate()) { if (!item->isStandaloneCoordinate()) { firstCoordinateItem = false; - VisualItemPair pair(lastCoordinateItem, item); if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) { - _addWaypointLineSegment(old_table, pair); + if (_editMode) { + VisualItemPair pair(lastCoordinateItem, item); + _addWaypointLineSegment(old_table, pair); + } else { + _waypointPath.append(QVariant::fromValue(item->coordinate())); + } } lastCoordinateItem = item; } } } if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) { - VisualItemPair pair(lastCoordinateItem, _settingsItem); - _addWaypointLineSegment(old_table, pair); + if (_editMode) { + VisualItemPair pair(lastCoordinateItem, _settingsItem); + _addWaypointLineSegment(old_table, pair); + } else { + _waypointPath.append(QVariant::fromValue(_settingsItem->coordinate())); + } } { @@ -1077,7 +1086,16 @@ void MissionController::_recalcWaypointLines(void) _recalcMissionFlightStatus(); + if (_waypointPath.count() == 0) { + // MapPolyLine has a bug where if you can from a path which has elements to an empty path the line drawn + // is not cleared from the map. This hack works around that since it causes the previous lines to be remove + // as then doesn't draw anything on the map. + _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0))); + _waypointPath.append(QVariant::fromValue(QGeoCoordinate(0, 0))); + } + emit waypointLinesChanged(); + emit waypointPathChanged(); } void MissionController::_updateBatteryInfo(int waypointIndex) diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index de2825f50..80e61ca43 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -66,7 +66,8 @@ public: } MissionFlightStatus_t; Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged) - Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) + Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) ///< Used by Plan view only for interactive editing + Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) @@ -146,6 +147,7 @@ public: QmlObjectListModel* visualItems (void) { return _visualItems; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; } + QVariantList waypointPath (void) { return _waypointPath; } QStringList complexMissionItemNames (void) const; QGeoCoordinate plannedHomePosition (void) const; VisualMissionItem* currentPlanViewItem (void) const; @@ -167,27 +169,28 @@ public: int batteriesRequired (void) const { return _missionFlightStatus.batteriesRequired; } ///< -1 for not supported signals: - void visualItemsChanged(void); - void waypointLinesChanged(void); - void newItemsFromVehicle(void); - void missionDistanceChanged(double missionDistance); - void missionTimeChanged(void); - void missionHoverDistanceChanged(double missionHoverDistance); - void missionHoverTimeChanged(void); - void missionCruiseDistanceChanged(double missionCruiseDistance); - void missionCruiseTimeChanged(void); - void missionMaxTelemetryChanged(double missionMaxTelemetry); - void complexMissionItemNamesChanged(void); - void resumeMissionIndexChanged(void); - void resumeMissionReady(void); - void resumeMissionUploadFail(void); - void batteryChangePointChanged(int batteryChangePoint); - void batteriesRequiredChanged(int batteriesRequired); - void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition); - void progressPctChanged(double progressPct); - void currentMissionIndexChanged(int currentMissionIndex); - void currentPlanViewIndexChanged(); - void currentPlanViewItemChanged(); + void visualItemsChanged (void); + void waypointLinesChanged (void); + void waypointPathChanged (void); + void newItemsFromVehicle (void); + void missionDistanceChanged (double missionDistance); + void missionTimeChanged (void); + void missionHoverDistanceChanged (double missionHoverDistance); + void missionHoverTimeChanged (void); + void missionCruiseDistanceChanged (double missionCruiseDistance); + void missionCruiseTimeChanged (void); + void missionMaxTelemetryChanged (double missionMaxTelemetry); + void complexMissionItemNamesChanged (void); + void resumeMissionIndexChanged (void); + void resumeMissionReady (void); + void resumeMissionUploadFail (void); + void batteryChangePointChanged (int batteryChangePoint); + void batteriesRequiredChanged (int batteriesRequired); + void plannedHomePositionChanged (QGeoCoordinate plannedHomePosition); + void progressPctChanged (double progressPct); + void currentMissionIndexChanged (int currentMissionIndex); + void currentPlanViewIndexChanged (void); + void currentPlanViewItemChanged (void); private slots: void _newMissionItemsAvailableFromVehicle(bool removeAllRequested); @@ -242,6 +245,7 @@ private: QmlObjectListModel* _visualItems; MissionSettingsItem* _settingsItem; QmlObjectListModel _waypointLines; + QVariantList _waypointPath; CoordVectHashTable _linesTable; bool _firstItemsFromVehicle; bool _itemsRequested; diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index 0bf450187..4ed0dcc33 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -214,11 +214,6 @@ void MissionManager::generateResumeMission(int resumeIndex) } _resumeMission = true; _writeMissionItemsWorker(); - - // Clean up no longer needed resume items - for (int i=0; ideleteLater(); - } } /// Called when a new mavlink message for out vehicle is received diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index be0321b23..5fdc161d0 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -85,8 +85,8 @@ void PlanManager::writeMissionItems(const QList& missionItems) int firstIndex = skipFirstItem ? 1 : 0; for (int i=firstIndex; isetIsCurrentItem(i == firstIndex); @@ -911,7 +911,8 @@ void PlanManager::removeAll(void) void PlanManager::_clearAndDeleteMissionItems(void) { for (int i=0; i<_missionItems.count(); i++) { - _missionItems[i]->deleteLater(); + // Using deleteLater here causes too much transient memory to stack up + delete _missionItems[i]; } _missionItems.clear(); } @@ -920,7 +921,8 @@ void PlanManager::_clearAndDeleteMissionItems(void) void PlanManager::_clearAndDeleteWriteMissionItems(void) { for (int i=0; i<_writeMissionItems.count(); i++) { - _writeMissionItems[i]->deleteLater(); + // Using deleteLater here causes too much transient memory to stack up + delete _writeMissionItems[i]; } _writeMissionItems.clear(); } diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index aeda03a50..cc2fb975b 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -47,6 +47,7 @@ public: void loadFromVehicle(void); /// Writes the specified set of mission items to the vehicle + /// IMPORTANT NOTE: PlanManager will take control of the MissionItem objects with the missionItems list. It will free them when done. /// @param missionItems Items to send to vehicle /// Signals sendComplete when done void writeMissionItems(const QList& missionItems); diff --git a/src/MissionManager/SectionTest.cc b/src/MissionManager/SectionTest.cc index e177504ea..f3c72c1e9 100644 --- a/src/MissionManager/SectionTest.cc +++ b/src/MissionManager/SectionTest.cc @@ -37,7 +37,7 @@ void SectionTest::init(void) 70.1234567, true, // autoContinue false); // isCurrentItem - _simpleItem = new SimpleMissionItem(_offlineVehicle, missionItem); + _simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); } void SectionTest::cleanup(void) @@ -77,7 +77,7 @@ void SectionTest::_commonScanTest(Section* section) QmlObjectListModel waypointVisualItems; MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false); - SimpleMissionItem simpleItem(_offlineVehicle, waypointItem); + SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, waypointItem); waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem); diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 4676fd462..132505f57 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -85,7 +85,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); } -SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent) +SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent) : VisualMissionItem(vehicle, parent) , _missionItem(missionItem) , _rawEdit(false) @@ -111,11 +111,16 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio _altitudeRelativeToHomeFact.setRawValue(true); _isCurrentItem = missionItem.isCurrentItem(); - _setupMetaData(); + // In !editMode we skip some of the intialization to save memory + if (editMode) { + _setupMetaData(); + } _connectSignals(); _updateOptionalSections(); _syncFrameToAltitudeRelativeToHome(); - _rebuildFacts(); + if (editMode) { + _rebuildFacts(); + } } SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent) diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index 047965829..c316804de 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -24,7 +24,7 @@ class SimpleMissionItem : public VisualMissionItem public: SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL); - SimpleMissionItem(Vehicle* vehicle, const MissionItem& missionItem, QObject* parent = NULL); + SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent = NULL); SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL); ~SimpleMissionItem(); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index 34ae7f19e..453987813 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -100,7 +100,7 @@ void SimpleMissionItemTest::init(void) 70.1234567, true, // autoContinue false); // isCurrentItem - _simpleItem = new SimpleMissionItem(_offlineVehicle, missionItem); + _simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); // It's important top check that the right signals are emitted at the right time since that drives ui change. // It's also important to check that things are not being over-signalled when they should not be, since that can lead @@ -139,7 +139,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem simpleMissionItem(vehicle, missionItem); + SimpleMissionItem simpleMissionItem(vehicle, true /* editMode */, missionItem); // Validate that the fact values are correctly returned diff --git a/src/MissionManager/SpeedSectionTest.cc b/src/MissionManager/SpeedSectionTest.cc index 37a89776e..b62db1c56 100644 --- a/src/MissionManager/SpeedSectionTest.cc +++ b/src/MissionManager/SpeedSectionTest.cc @@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, missionItem); + SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); QVERIFY(item->speedSection()); QCOMPARE(item->speedSection()->available(), false); } @@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void) double flightSpeed = 10.123456; MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false); - SimpleMissionItem simpleItem(_offlineVehicle, validSpeedItem); + SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, validSpeedItem); MissionItem& simpleMissionItem = simpleItem.missionItem(); visualItems.append(&simpleItem); scanIndex = 0; @@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void) // Valid item in wrong position QmlObjectListModel waypointVisualItems; MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false); - SimpleMissionItem simpleWaypointItem(_offlineVehicle, waypointMissionItem); + SimpleMissionItem simpleWaypointItem(_offlineVehicle, true /* editMode */, waypointMissionItem); simpleMissionItem = validSpeedItem; visualItems.append(&simpleWaypointItem); visualItems.append(&simpleMissionItem); -- 2.22.0