diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index a31bfed2829fb509f0472970ef67ca464b3f64f8..7d35bb7accf500c6245a0a87200f9ac181fa4475 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -592,7 +592,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Check for a scan success - SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidGimbalItem->missionItem() = _validGimbalItem->missionItem(); visualItems.append(newValidGimbalItem); scanIndex = 0; @@ -676,7 +676,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) // Check for a scan success - SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem(); visualItems.append(newValidCameraModeItem); scanIndex = 0; @@ -735,7 +735,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) Mission Param #3 Number of images to capture total - 0 for unlimited capture */ - SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidTimeItem->missionItem() = _validTimeItem->missionItem(); visualItems.append(newValidTimeItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -776,7 +776,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) Mission Param #7 Empty */ - SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidDistanceItem->missionItem() = _validDistanceItem->missionItem(); visualItems.append(newValidDistanceItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -862,7 +862,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) Mission Param #3 Reserved */ - SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem(); visualItems.append(newValidStartVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -898,7 +898,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) Mission Param #1 Reserved (Set to 0) */ - SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem(); visualItems.append(newValidStopVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -936,8 +936,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) _commonScanTest(_cameraSection); - SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); - SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); + SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem(); newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem(); visualItems.append(newValidStopDistanceItem); @@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) // Out of order commands - SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, nullptr); - SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); + SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem(); validStopTimeItem.missionItem() = _validStopTimeItem->missionItem(); visualItems.append(&validStopTimeItem); @@ -979,7 +979,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) Mission Param #4 0 Unused sequence id */ - SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem(); visualItems.append(newValidTakePhotoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -1051,9 +1051,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Camera action followed by gimbal/mode for (SimpleMissionItem* actionItem: rgActionItems) { for (SimpleMissionItem* cameraItem: rgCameraItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); @@ -1072,9 +1072,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Gimbal/Mode followed by camera action for (SimpleMissionItem* actionItem: rgCameraItems) { for (SimpleMissionItem* cameraItem: rgActionItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); diff --git a/src/MissionManager/FWLandingPatternTest.cc b/src/MissionManager/FWLandingPatternTest.cc index 035329b0598a632e6a964cc14736a653e2961988..87f439ee80c5c7cdb6ab68a880d7f2f4bf0a3781 100644 --- a/src/MissionManager/FWLandingPatternTest.cc +++ b/src/MissionManager/FWLandingPatternTest.cc @@ -97,7 +97,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) QmlObjectListModel* simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } @@ -118,7 +118,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) _fwItem->appendMissionItems(rgMissionItems, this); simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 57e142f9be1cbad8b23e2b8d25282ab7da44a3de..6a221ab0fda36e78b559572d7d9552041903a7e3 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -359,7 +359,7 @@ int MissionController::_nextSequenceNumber(void) VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem) { int sequenceNumber = _nextSequenceNumber(); - SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); + SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, false /* forLoad */, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); newItem->setCommand(command); @@ -673,7 +673,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); if (json.contains(_jsonPlannedHomePositionKey)) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems); if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { settingsItem->setInitialHomePositionFromUser(item->coordinate()); item->deleteLater(); @@ -709,11 +709,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec } const QJsonObject itemObject = itemValue.toObject(); - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems); if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString); item->deleteLater(); item = takeoffItem; @@ -797,11 +797,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString(); if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems); if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) { if (TakeoffMissionItem::isTakeoffCommand(static_cast(simpleItem->command()))) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, this); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, this); takeoffItem->load(itemObject, nextSequenceNumber, errorString); simpleItem->deleteLater(); simpleItem = takeoffItem; @@ -941,14 +941,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); while (!stream.atEnd()) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems); if (item->load(stream)) { if (firstItem && plannedHomePositionInFile) { settingsItem->setInitialHomePositionFromUser(item->coordinate()); } else { if (TakeoffMissionItem::isTakeoffCommand(static_cast(item->command()))) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(stream); item->deleteLater(); item = takeoffItem; diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index ddee6ee619caa7889605d9e43fe6d92a2f1b5b3c..8b43b4dcafd430615856eac962df40a2a5a21615 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -281,7 +281,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void) { // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n"); QTextStream testStream(&testString, QIODevice::ReadOnly); @@ -451,7 +451,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void) // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); QString errorString; QJsonArray coordinateArray; QJsonObject jsonObject; diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index a5b853144b003f6fecb3bee95c3d45a0cf89a1a6..bd9fa0e3724bf9488ee06c4086d70e7888373653 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -51,7 +51,7 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, }; -SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) +SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent) : VisualMissionItem (vehicle, flyView, parent) , _rawEdit (false) , _dirty (false) @@ -75,13 +75,15 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* pa _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); _setupMetaData(); - _connectSignals(); - _updateOptionalSections(); - - _setDefaultsForCommand(); - _rebuildFacts(); - setDirty(false); + if (!forLoad) { + // We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done + _connectSignals(); + _updateOptionalSections(); + _setDefaultsForCommand(); + _rebuildFacts(); + setDirty(false); + } } SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent) @@ -295,7 +297,10 @@ bool SimpleMissionItem::load(QTextStream &loadStream) _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue()); _amslAltAboveTerrainFact.setRawValue(qQNaN()); } + _connectSignals(); _updateOptionalSections(); + _rebuildFacts(); + setDirty(false); } return success; @@ -328,7 +333,10 @@ bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QStrin } } + _connectSignals(); _updateOptionalSections(); + _rebuildFacts(); + setDirty(false); return true; } diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index ff065dca502433b9fe979878cb715418ab56fea5..a89ab40701bb8bc237f2a97c81cd918ccc5f96d7 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -24,9 +24,8 @@ class SimpleMissionItem : public VisualMissionItem Q_OBJECT public: - SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent); + SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent); SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent); - //SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent); ~SimpleMissionItem(); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index a5b023d77d378282c351753c75db370e6176b64d..52296face99a969c7d495084a00755186cd556f7 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) void SimpleMissionItemTest::_testDefaultValues(void) { - SimpleMissionItem item(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem item(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT); item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index 8d5d981e5f4914dccb17b005e5cd6052aa5dde74..cb2e03c004612bc985139e9ec2a162a8a2b3b13c 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -19,26 +19,26 @@ #include "QGroundControlQmlGlobal.h" #include "SettingsManager.h" -TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (vehicle, flyView, parent) +TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent) + : SimpleMissionItem (vehicle, flyView, forLoad, parent) , _settingsItem (settingsItem) { - _init(); + _init(forLoad); } TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (vehicle, flyView, parent) + : SimpleMissionItem (vehicle, flyView, false /* forLoad */, parent) , _settingsItem (settingsItem) { setCommand(takeoffCmd); - _init(); + _init(false /* forLoad */); } TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) : SimpleMissionItem (vehicle, flyView, missionItem, parent) , _settingsItem (settingsItem) { - _init(); + _init(false /* forLoad */); _wizardMode = false; } @@ -47,7 +47,7 @@ TakeoffMissionItem::~TakeoffMissionItem() } -void TakeoffMissionItem::_init(void) +void TakeoffMissionItem::_init(bool forLoad) { _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); @@ -69,6 +69,11 @@ void TakeoffMissionItem::_init(void) } } + if (forLoad) { + // Load routines will set the rest up after load + return; + } + _initLaunchTakeoffAtSameLocation(); if (homePosition.isValid() && coordinate().isValid()) { diff --git a/src/MissionManager/TakeoffMissionItem.h b/src/MissionManager/TakeoffMissionItem.h index d4f3ce92fff6d438e89f74882dfee433b603832b..843278c8e0e862282f5498a047db2641c00b91c0 100644 --- a/src/MissionManager/TakeoffMissionItem.h +++ b/src/MissionManager/TakeoffMissionItem.h @@ -19,7 +19,7 @@ class TakeoffMissionItem : public SimpleMissionItem Q_OBJECT public: - TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); + TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent); TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); @@ -55,7 +55,7 @@ signals: void launchTakeoffAtSameLocationChanged (bool launchTakeoffAtSameLocation); private: - void _init(void); + void _init(bool forLoad); void _initLaunchTakeoffAtSameLocation(void); MissionSettingsItem* _settingsItem; diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index ca21c6baf0c55a24f801fd6e30f6432a212f68a3..fb2c26f9704d722d13948013369ce7a173aca679 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -498,7 +498,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList