diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index d363af171652dfdbddcfb00891398558f89f51a6..85a4876103580b9705f19228cbf6537d77fa8344 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -109,7 +109,7 @@ QGCView { PlanMasterController { id: masterController - Component.onCompleted: start(false /* editMode */) + Component.onCompleted: start(true /* flyView */) } Connections { diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 76894ede9693c70d3445922208ca6999c1258d6f..81225f4e5150b72643d3f819526022001e52a082 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -46,15 +46,15 @@ void CameraSectionTest::init(void) QVERIFY(_spySection); _validGimbalItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView 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 + false, // flyView 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 + false, // flyView MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, @@ -65,7 +65,7 @@ void CameraSectionTest::init(void) true, false), this); _validStartVideoItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView MissionItem(0, // sequence number MAV_CMD_VIDEO_START_CAPTURE, MAV_FRAME_MISSION, @@ -76,19 +76,19 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validStopVideoItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView 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 + false, // flyView 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 + false, // flyView 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 + false, // flyView MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -99,7 +99,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validCameraVideoModeItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -110,7 +110,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validCameraSurveyPhotoModeItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView MissionItem(0, // sequence number MAV_CMD_SET_CAMERA_MODE, MAV_FRAME_MISSION, @@ -121,7 +121,7 @@ void CameraSectionTest::init(void) false), // isCurrentItem this); _validTakePhotoItem = new SimpleMissionItem(_offlineVehicle, - true, // editMode + false, // flyView MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, @@ -362,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); + SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this); QVERIFY(item->cameraSection()); QCOMPARE(item->cameraSection()->available(), false); } @@ -606,7 +606,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Check for a scan success - SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidGimbalItem->missionItem() = _validGimbalItem->missionItem(); visualItems.append(newValidGimbalItem); scanIndex = 0; @@ -633,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Gimbal command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validGimbalItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam2(10); // roll is not supported visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -690,7 +690,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) // Check for a scan success - SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem(); visualItems.append(newValidCameraModeItem); scanIndex = 0; @@ -723,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) */ // Mode command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validCameraPhotoModeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -749,7 +749,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) Mission Param #3 Number of images to capture total - 0 for unlimited capture */ - SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidTimeItem->missionItem() = _validTimeItem->missionItem(); visualItems.append(newValidTimeItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -762,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) // Image start command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -790,7 +790,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) Mission Param #7 Empty */ - SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidDistanceItem->missionItem() = _validDistanceItem->missionItem(); visualItems.append(newValidDistanceItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -803,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validDistanceItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -876,7 +876,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) Mission Param #3 Reserved */ - SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem(); visualItems.append(newValidStartVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -888,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) // Start Video command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStartVideoItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0) visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -912,7 +912,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) Mission Param #1 Reserved (Set to 0) */ - SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem(); visualItems.append(newValidStopVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -924,7 +924,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStopVideoItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam1(10); // must be 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopImageSection(void) _commonScanTest(_cameraSection); - SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, this); - SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem(); newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem(); visualItems.append(newValidStopDistanceItem); @@ -964,8 +964,8 @@ void CameraSectionTest::_testScanForStopImageSection(void) // Out of order commands - SimpleMissionItem validStopDistanceItem(_offlineVehicle); - SimpleMissionItem validStopTimeItem(_offlineVehicle); + SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, NULL); + SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, NULL); validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem(); validStopTimeItem.missionItem() = _validStopTimeItem->missionItem(); visualItems.append(&validStopTimeItem); @@ -993,7 +993,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) Mission Param #4 Reserved */ - SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem(); visualItems.append(newValidTakePhotoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -1005,7 +1005,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) // Take Photo command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem()); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL); invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -1065,9 +1065,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Camera action followed by gimbal/mode foreach (SimpleMissionItem* actionItem, rgActionItems) { foreach (SimpleMissionItem* cameraItem, rgCameraItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); @@ -1086,9 +1086,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Gimbal/Mode followed by camera action foreach (SimpleMissionItem* actionItem, rgCameraItems) { foreach (SimpleMissionItem* cameraItem, rgActionItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc index 43075c1ee119556264c8c6f4189bdac7ce330e64..44af71895fa2eb43d483f72186a3baab7fb606ab 100644 --- a/src/MissionManager/ComplexMissionItem.cc +++ b/src/MissionManager/ComplexMissionItem.cc @@ -11,8 +11,8 @@ const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType"; -ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent) - : VisualMissionItem(vehicle, parent) +ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) + : VisualMissionItem(vehicle, flyView, parent) { } diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index bc27fe7f80856a77f750925fb21b734bcc5fab0a..dc1b0d661e3780f049f9c7381f816f0d16ab6f9b 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -17,7 +17,7 @@ class ComplexMissionItem : public VisualMissionItem Q_OBJECT public: - ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL); + ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent); const ComplexMissionItem& operator=(const ComplexMissionItem& other); diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index 7b44997cbfd3bf6cf03c7ccf176fb3609ec1225d..5d8bff23ec46be99730268e873e6639af1e5b25b 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -27,8 +27,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint"; const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan"; -CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent) - : TransectStyleComplexItem (vehicle, settingsGroup, parent) +CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent) + : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent) , _entryPoint (0) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this)) , _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName]) diff --git a/src/MissionManager/CorridorScanComplexItem.h b/src/MissionManager/CorridorScanComplexItem.h index d9bd72671876716aeac2c20fca238f28d8f25dc9..0903dc4c4e5a230e247f87c62aec9077c396db83 100644 --- a/src/MissionManager/CorridorScanComplexItem.h +++ b/src/MissionManager/CorridorScanComplexItem.h @@ -23,7 +23,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem Q_OBJECT public: - CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); + CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent); Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT) Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT) diff --git a/src/MissionManager/CorridorScanComplexItemTest.cc b/src/MissionManager/CorridorScanComplexItemTest.cc index ede44ac12ab54bd1543fb021e7560dfea818e046..142e2a0db3b1cd17a8ebc6eac9c7307e981b19c4 100644 --- a/src/MissionManager/CorridorScanComplexItemTest.cc +++ b/src/MissionManager/CorridorScanComplexItemTest.cc @@ -23,7 +23,7 @@ void CorridorScanComplexItemTest::init(void) UnitTest::init(); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); - _corridorItem = new CorridorScanComplexItem(_offlineVehicle, this); + _corridorItem = new CorridorScanComplexItem(_offlineVehicle, false /* flyView */, this); // vehicleSpeed need for terrain calcs MissionController::MissionFlightStatus_t missionFlightStatus; diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index 9e1beb939d9cee126ef5b12e716a15a9cfb5bc5b..18873b703796ac5f04645573e1e3f40e7787deea 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -39,8 +39,8 @@ const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fal const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative"; const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative"; -FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent) - : ComplexMissionItem (vehicle, parent) +FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent) + : ComplexMissionItem (vehicle, flyView, parent) , _sequenceNumber (0) , _dirty (false) , _landingCoordSet (false) @@ -283,7 +283,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList& items, items.append(item); } -bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle) +bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle) { qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count(); @@ -328,7 +328,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V // We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission - FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, visualItems); + FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, flyView, visualItems); complexItem->_ignoreRecalcSignals = true; diff --git a/src/MissionManager/FixedWingLandingComplexItem.h b/src/MissionManager/FixedWingLandingComplexItem.h index c04d66f614253f4c6e6ebca69837e022daf0807b..cc08a0996787b192ba06cfc8c79de0f88f4b3679 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.h +++ b/src/MissionManager/FixedWingLandingComplexItem.h @@ -22,7 +22,7 @@ class FixedWingLandingComplexItem : public ComplexMissionItem Q_OBJECT public: - FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent = NULL); + FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent); Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT) Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT) @@ -52,7 +52,7 @@ public: void setLoiterCoordinate (const QGeoCoordinate& coordinate); /// Scans the loaded items for a landing pattern complex item - static bool scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle); + static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle); // Overrides from ComplexMissionItem diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index ce1ec212e80aaf477b92816573e81a128b7aff1c..5e6d3de185019cbf0d6f0b95a3f0083e04632d26 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -54,11 +54,11 @@ GeoFenceController::~GeoFenceController() } -void GeoFenceController::start(bool editMode) +void GeoFenceController::start(bool flyView) { - qCDebug(GeoFenceControllerLog) << "start editMode" << editMode; + qCDebug(GeoFenceControllerLog) << "start flyView" << flyView; - PlanElementController::start(editMode); + PlanElementController::start(flyView); _init(); } @@ -269,7 +269,7 @@ void GeoFenceController::_managerLoadComplete(void) { // Fly view always reloads on _loadComplete // Plan view only reloads on _loadComplete if specifically requested - if (!_editMode || _itemsRequested) { + if (_flyView || _itemsRequested) { _setReturnPointFromManager(_geoFenceManager->breachReturnPoint()); _setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles()); setDirty(false); @@ -282,7 +282,7 @@ void GeoFenceController::_managerLoadComplete(void) void GeoFenceController::_managerSendComplete(bool error) { // Fly view always reloads on manager sendComplete - if (!error && !_editMode) { + if (!error && _flyView) { showPlanFromManagerVehicle(); } } @@ -307,7 +307,7 @@ void GeoFenceController::_updateContainsItems(void) bool GeoFenceController::showPlanFromManagerVehicle(void) { - qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle" << _editMode; + qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView; if (_masterController->offline()) { qCWarning(GeoFenceControllerLog) << "GeoFenceController::showPlanFromManagerVehicle called while offline"; return true; // stops further propagation of showPlanFromManagerVehicle due to error diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index 87b15766ada2c8d5da701d6adb57c633697d03b9..f6c5dfbbf6ae013906d2bd8b62af9126e08a0d19 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -62,7 +62,7 @@ public: // Overrides from PlanElementController bool supported (void) const final; - void start (bool editMode) final; + void start (bool flyView) final; void save (QJsonObject& json) final; bool load (const QJsonObject& json, QString& errorString) final; void loadFromVehicle (void) final; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 3fbe7327df111253009fee7833f6883cf6d3b050..e518d4a64c3e418b9f2d6fb3c77dcf4f32c24ef2 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -123,11 +123,11 @@ void MissionController::_resetMissionFlightStatus(void) } -void MissionController::start(bool editMode) +void MissionController::start(bool flyView) { - qCDebug(MissionControllerLog) << "start editMode" << editMode; + qCDebug(MissionControllerLog) << "start flyView" << flyView; - PlanElementController::start(editMode); + PlanElementController::start(flyView); _init(); } @@ -146,7 +146,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque // Fly view always reloads on _loadComplete // Plan view only reloads on _loadComplete if specifically requested - if (!_editMode || removeAllRequested || _itemsRequested) { + if (_flyView || removeAllRequested || _itemsRequested) { // Fly Mode (accept if): // - Always accepts new items from the vehicle so Fly view is kept up to date // Edit Mode (accept if): @@ -176,7 +176,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque for (; iappend(new SimpleMissionItem(_controllerVehicle, _editMode, *missionItem, this)); + newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this)); } _deinitAllVisualItems(); @@ -187,7 +187,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque _visualItems = newControllerMissionItems; if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) { - _addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */); + _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */); } MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle); @@ -331,7 +331,7 @@ int MissionController::_nextSequenceNumber(void) int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) { int sequenceNumber = _nextSequenceNumber(); - SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this); + SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); newItem->setCommand(MAV_CMD_NAV_WAYPOINT); @@ -363,7 +363,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i) { int sequenceNumber = _nextSequenceNumber(); - SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this); + SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ? MAV_CMD_DO_SET_ROI_LOCATION : @@ -393,15 +393,15 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate int sequenceNumber = _nextSequenceNumber(); if (itemName == _surveyMissionItemName) { - newItem = new SurveyComplexItem(_controllerVehicle, _visualItems); + newItem = new SurveyComplexItem(_controllerVehicle, _flyView, _visualItems); newItem->setCoordinate(mapCenterCoordinate); surveyStyleItem = true; } else if (itemName == _fwLandingMissionItemName) { - newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems); + newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems); } else if (itemName == _structureScanMissionItemName) { - newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems); + newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, _visualItems); } else if (itemName == _corridorScanMissionItemName) { - newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems); + newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, _visualItems); surveyStyleItem = true; } else { qWarning() << "Internal error: Unknown complex item:" << itemName; @@ -529,7 +529,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec return false; } - SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, visualItems); + SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, visualItems); const QJsonObject itemObject = itemValue.toObject(); if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { surveyItems.append(item); @@ -572,7 +572,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec } const QJsonObject itemObject = itemValue.toObject(); - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber(); nextSequenceNumber = item->lastSequenceNumber() + 1; @@ -584,10 +584,10 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count()); if (json.contains(_jsonPlannedHomePositionKey)) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { - MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems); settingsItem->setCoordinate(item->coordinate()); visualItems->insert(0, settingsItem); item->deleteLater(); @@ -639,7 +639,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) { return false; } - MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems); settingsItem->setCoordinate(homeCoordinate); visualItems->insert(0, settingsItem); qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate; @@ -668,7 +668,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString(); if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) { qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command(); nextSequenceNumber = simpleItem->lastSequenceNumber() + 1; @@ -687,7 +687,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber; - SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, visualItems); + SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, visualItems); if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -696,7 +696,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec visualItems->append(surveyItem); } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber; - FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems); + FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems); if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -705,7 +705,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec visualItems->append(landingItem); } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber; - StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems); + StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, visualItems); if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -714,7 +714,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec visualItems->append(structureItem); } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber; - CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems); + CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, visualItems); if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -723,7 +723,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec visualItems->append(corridorItem); } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) { qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber; - MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems); if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) { return false; } @@ -816,7 +816,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM MissionSettingsItem* settingsItem = visualItems->value(0); while (!stream.atEnd()) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); if (item->load(stream)) { if (firstItem && plannedHomePositionInFile) { @@ -1080,7 +1080,7 @@ void MissionController::_recalcWaypointLines(void) if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) { firstCoordinateItem = false; if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) { - if (_editMode) { + if (!_flyView) { VisualItemPair pair(lastCoordinateItem, item); _addWaypointLineSegment(old_table, pair); } @@ -1095,7 +1095,7 @@ void MissionController::_recalcWaypointLines(void) } if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) { - if (_editMode) { + if (!_flyView) { VisualItemPair pair(lastCoordinateItem, _settingsItem); _addWaypointLineSegment(old_table, pair); } else { @@ -1503,7 +1503,7 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void) void MissionController::_recalcAll(void) { - if (_editMode) { + if (!_flyView) { _setPlannedHomePositionFromFirstCoordinate(); } _recalcSequence(); @@ -1521,7 +1521,7 @@ void MissionController::_initAllVisualItems(void) qWarning() << "First item not MissionSettingsItem"; return; } - if (_editMode) { + if (!_flyView) { _settingsItem->setIsCurrentItem(true); } @@ -1716,7 +1716,7 @@ double MissionController::_normalizeLon(double lon) /// Add the Mission Settings complex item to the front of the items void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter) { - MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems); + MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems); qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter; @@ -1764,7 +1764,7 @@ int MissionController::resumeMissionIndex(void) const int resumeIndex = 0; - if (!_editMode) { + if (_flyView) { resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1); if (resumeIndex > 1 && resumeIndex != _visualItems->value(_visualItems->count() - 1)->sequenceNumber()) { // Resume at the item previous to the item we were heading towards @@ -1779,7 +1779,7 @@ int MissionController::resumeMissionIndex(void) const int MissionController::currentMissionIndex(void) const { - if (_editMode) { + if (!_flyView) { return -1; } else { int currentIndex = _missionManager->currentIndex(); @@ -1792,7 +1792,7 @@ int MissionController::currentMissionIndex(void) const void MissionController::_currentMissionIndexChanged(int sequenceNumber) { - if (!_editMode) { + if (_flyView) { if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) { sequenceNumber++; } @@ -1825,9 +1825,9 @@ void MissionController::setDirty(bool dirty) void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle) { - if (_editMode) { + if (!_flyView) { // First we look for a Fixed Wing Landing Pattern which is at the end - FixedWingLandingComplexItem::scanForItem(visualItems, vehicle); + FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle); } int scanIndex = 0; @@ -1836,7 +1836,7 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex; - if (_editMode) { + if (!_flyView) { MissionSettingsItem* settingsItem = qobject_cast(visualItem); if (settingsItem) { scanIndex++; @@ -1937,7 +1937,7 @@ void MissionController::_visualItemsDirtyChanged(bool dirty) bool MissionController::showPlanFromManagerVehicle (void) { - qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode; + qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView; if (_masterController->offline()) { qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline"; return true; // stops further propagation of showPlanFromManagerVehicle due to error @@ -1963,7 +1963,7 @@ bool MissionController::showPlanFromManagerVehicle (void) void MissionController::_managerSendComplete(bool error) { // Fly view always reloads on send complete - if (!error && !_editMode) { + if (!error && _flyView) { showPlanFromManagerVehicle(); } } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index ba75d962f15ee5778ebef71ac197e07263fcebd4..54c4469b4179c62038b6f9c917345370ff58bd2c 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -129,7 +129,7 @@ public: // Overrides from PlanElementController bool supported (void) const final { return true; } - void start (bool editMode) final; + void start (bool flyView) final; void save (QJsonObject& json) final; bool load (const QJsonObject& json, QString& errorString) final; void loadFromVehicle (void) final; diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc index ef7946246d32e57f73fc99b8749798e19f3bd180..de06cccfff75035fcf8242e981923bc65f236883 100644 --- a/src/MissionManager/MissionControllerTest.cc +++ b/src/MissionManager/MissionControllerTest.cc @@ -59,7 +59,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) Q_CHECK_PTR(_multiSpyMissionController); QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true); - _masterController->start(true /* editMode */); + _masterController->start(false /* flyView */); // All signals should some through on start QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true); @@ -166,7 +166,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp // Start offline and add item _missionController = new MissionController(); Q_CHECK_PTR(_missionController); - _missionController->start(true /* editMode */); + _missionController->start(false /* flyView */); _missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count()); // Go online to empty vehicle diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index 1480af7ade69dbcbaa502d373d12cd6fc60d7d9f..f4ed23e4ff9ff3e65d17d9b0385a9ab44548786e 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void) { // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL); QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n"); QTextStream testStream(&testString, QIODevice::ReadOnly); @@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void) // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL); QString errorString; QJsonArray coordinateArray; QJsonObject jsonObject; diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index 47d3971279cac9ba1c853007760914db96a395a1..af784e7657642303936efb28747395eefde5e52e 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -27,9 +27,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome QMap MissionSettingsItem::_metaDataMap; -MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool planView, QObject* parent) - : ComplexMissionItem (vehicle, parent) - , _planView (planView) +MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent) + : ComplexMissionItem (vehicle, flyView, parent) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) , _plannedHomePositionFromVehicle (false) , _missionEndRTL (false) @@ -303,5 +302,5 @@ void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude) QString MissionSettingsItem::abbreviation(void) const { - return _planView ? tr("Planned Home") : tr("H"); + return _flyView ? tr("H") : tr("Planned Home"); } diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h index d4935d1db9baca4307d0dd7e6a6a01a35bbcd64b..2a031217578ecdc357eef70e1ee778e6ab1336bc 100644 --- a/src/MissionManager/MissionSettingsItem.h +++ b/src/MissionManager/MissionSettingsItem.h @@ -24,7 +24,7 @@ class MissionSettingsItem : public ComplexMissionItem Q_OBJECT public: - MissionSettingsItem(Vehicle* vehicle, bool planView, QObject* parent = NULL); + MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent); Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) Q_PROPERTY(bool missionEndRTL READ missionEndRTL WRITE setMissionEndRTL NOTIFY missionEndRTLChanged) @@ -101,7 +101,6 @@ private slots: void _setHomeAltFromTerrain (double terrainAltitude); private: - bool _planView; QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude Fact _plannedHomePositionAltitudeFact; bool _plannedHomePositionFromVehicle; diff --git a/src/MissionManager/MissionSettingsTest.cc b/src/MissionManager/MissionSettingsTest.cc index df6cd8f5ecf9b5630a3db7e25207f7283aea6bea..4688d5afbd2daf6cc7f7450df960aacb815a0ec0 100644 --- a/src/MissionManager/MissionSettingsTest.cc +++ b/src/MissionManager/MissionSettingsTest.cc @@ -22,7 +22,7 @@ void MissionSettingsTest::init(void) { VisualMissionItemTest::init(); - _settingsItem = new MissionSettingsItem(_offlineVehicle, true /* planView */, this); + _settingsItem = new MissionSettingsItem(_offlineVehicle, false /* flyView */, this); } void MissionSettingsTest::cleanup(void) diff --git a/src/MissionManager/PlanElementController.cc b/src/MissionManager/PlanElementController.cc index 0ec882bde185b7d7821056cf8b66d319ebf2c269..f83cfad032e2c6759d41e273b781700b0fa9bc64 100644 --- a/src/MissionManager/PlanElementController.cc +++ b/src/MissionManager/PlanElementController.cc @@ -15,11 +15,11 @@ #include "AppSettings.h" PlanElementController::PlanElementController(PlanMasterController* masterController, QObject* parent) - : QObject(parent) - , _masterController(masterController) + : QObject (parent) + , _masterController (masterController) , _controllerVehicle(masterController->controllerVehicle()) - , _managerVehicle(masterController->managerVehicle()) - , _editMode(false) + , _managerVehicle (masterController->managerVehicle()) + , _flyView (false) { } @@ -29,9 +29,9 @@ PlanElementController::~PlanElementController() } -void PlanElementController::start(bool editMode) +void PlanElementController::start(bool flyView) { - _editMode = editMode; + _flyView = flyView; } void PlanElementController::managerVehicleChanged(Vehicle* managerVehicle) diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index 473c19e67a0f68cc7eeb299df30f024f67476194..0690c84be5cf63a3b6f99d3fddb39ec30688b5f3 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -33,8 +33,7 @@ public: Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send /// Should be called immediately upon Component.onCompleted. - /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view - virtual void start(bool editMode); + virtual void start(bool flyView); virtual void save (QJsonObject& json) = 0; virtual bool load (const QJsonObject& json, QString& errorString) = 0; @@ -72,7 +71,7 @@ protected: PlanMasterController* _masterController; Vehicle* _controllerVehicle; ///< Offline controller vehicle Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none - bool _editMode; + bool _flyView; }; #endif diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index 8d96d2cca8a3951ea56a0bb6da75db030005f8c5..c0638ccca8d6d606923103646418906dd90c84ff 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -29,20 +29,20 @@ const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence"; const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints"; PlanMasterController::PlanMasterController(QObject* parent) - : QObject(parent) - , _multiVehicleMgr(qgcApp()->toolbox()->multiVehicleManager()) - , _controllerVehicle(new Vehicle((MAV_AUTOPILOT)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt(), (MAV_TYPE)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt(), qgcApp()->toolbox()->firmwarePluginManager())) - , _managerVehicle(_controllerVehicle) - , _editMode(false) - , _offline(true) - , _missionController(this) - , _geoFenceController(this) - , _rallyPointController(this) - , _loadGeoFence(false) - , _loadRallyPoints(false) - , _sendGeoFence(false) - , _sendRallyPoints(false) - , _syncInProgress(false) + : QObject (parent) + , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) + , _controllerVehicle (new Vehicle((MAV_AUTOPILOT)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt(), (MAV_TYPE)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt(), qgcApp()->toolbox()->firmwarePluginManager())) + , _managerVehicle (_controllerVehicle) + , _flyView (true) + , _offline (true) + , _missionController (this) + , _geoFenceController (this) + , _rallyPointController (this) + , _loadGeoFence (false) + , _loadRallyPoints (false) + , _sendGeoFence (false) + , _sendRallyPoints (false) + , _syncInProgress (false) { connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); @@ -62,12 +62,12 @@ PlanMasterController::~PlanMasterController() } -void PlanMasterController::start(bool editMode) +void PlanMasterController::start(bool flyView) { - _editMode = editMode; - _missionController.start(editMode); - _geoFenceController.start(editMode); - _rallyPointController.start(editMode); + _flyView = flyView; + _missionController.start(_flyView); + _geoFenceController.start(_flyView); + _rallyPointController.start(_flyView); connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged); _activeVehicleChanged(_multiVehicleMgr->activeVehicle()); @@ -75,10 +75,10 @@ void PlanMasterController::start(bool editMode) void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle) { - _editMode = false; - _missionController.start(false); - _geoFenceController.start(false); - _rallyPointController.start(false); + _flyView = true; + _missionController.start(_flyView); + _geoFenceController.start(_flyView); + _rallyPointController.start(_flyView); _activeVehicleChanged(vehicle); } @@ -132,7 +132,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) _geoFenceController.managerVehicleChanged(_managerVehicle); _rallyPointController.managerVehicleChanged(_managerVehicle); - if (_editMode) { + if (!_flyView) { if (!offline()) { // We are in Plan view and we have a newly connected vehicle: // - If there is no plan available in Plan view show the one from the vehicle @@ -164,7 +164,7 @@ void PlanMasterController::loadFromVehicle(void) if (offline()) { qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while offline"; - } else if (!_editMode) { + } else if (_flyView) { qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called from Fly view"; } else if (syncInProgress()) { qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while syncInProgress"; @@ -181,7 +181,7 @@ void PlanMasterController::loadFromVehicle(void) void PlanMasterController::_loadMissionComplete(void) { - if (_editMode && _loadGeoFence) { + if (!_flyView && _loadGeoFence) { _loadGeoFence = false; _loadRallyPoints = true; if (_geoFenceController.supported()) { @@ -198,7 +198,7 @@ void PlanMasterController::_loadMissionComplete(void) void PlanMasterController::_loadGeoFenceComplete(void) { - if (_editMode && _loadRallyPoints) { + if (!_flyView && _loadRallyPoints) { _loadRallyPoints = false; if (_rallyPointController.supported()) { qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle"; @@ -214,7 +214,7 @@ void PlanMasterController::_loadGeoFenceComplete(void) void PlanMasterController::_loadRallyPointsComplete(void) { - if (_editMode) { + if (!_flyView) { _syncInProgress = false; emit syncInProgressChanged(false); } diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h index 6e618ed5a4cd938b7a24c3f37fd77869db501fda..f688b4e0501f0518b131b6a9ee2599b8c1e6bac8 100644 --- a/src/MissionManager/PlanMasterController.h +++ b/src/MissionManager/PlanMasterController.h @@ -46,8 +46,7 @@ public: Q_PROPERTY(QStringList saveKmlFilters READ saveKmlFilters CONSTANT) ///< File filter list saving KML files /// Should be called immediately upon Component.onCompleted. - /// @param editMode true: controller being used in Plan view, false: controller being used in Fly view - Q_INVOKABLE void start(bool editMode); + Q_INVOKABLE void start(bool flyView); /// Starts the controller using a single static active vehicle. Will not track global active vehicle changes. Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle); @@ -111,7 +110,7 @@ private: MultiVehicleManager* _multiVehicleMgr; Vehicle* _controllerVehicle; ///< Offline controller vehicle Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none - bool _editMode; + bool _flyView; bool _offline; MissionController _missionController; GeoFenceController _geoFenceController; diff --git a/src/MissionManager/PlanMasterControllerTest.cc b/src/MissionManager/PlanMasterControllerTest.cc index c27162bc3443dcfdef59d70111c33a05bda21ec4..eae62cb08b992f1f1ec1ec5030fdae606f7384f6 100644 --- a/src/MissionManager/PlanMasterControllerTest.cc +++ b/src/MissionManager/PlanMasterControllerTest.cc @@ -27,7 +27,7 @@ void PlanMasterControllerTest::init(void) UnitTest::init(); _masterController = new PlanMasterController(this); - _masterController->start(true /* editMode */); + _masterController->start(false /* flyView */); } void PlanMasterControllerTest::cleanup(void) diff --git a/src/MissionManager/RallyPointController.cc b/src/MissionManager/RallyPointController.cc index 24c0cde56687e227e832bf48edd6f1c5dbfc038e..ab52a8adf7d014b2c770ec6745f4d07bc90d789e 100644 --- a/src/MissionManager/RallyPointController.cc +++ b/src/MissionManager/RallyPointController.cc @@ -192,7 +192,7 @@ void RallyPointController::_managerLoadComplete(const QList rgPo { // Fly view always reloads on _loadComplete // Plan view only reloads on _loadComplete if specifically requested - if (!_editMode || _itemsRequested) { + if (_flyView || _itemsRequested) { _points.clearAndDeleteContents(); QObjectList pointList; for (int i=0; i rgPo void RallyPointController::_managerSendComplete(bool error) { // Fly view always reloads after send - if (!error && _editMode) { + if (!error && !_flyView) { showPlanFromManagerVehicle(); } } @@ -286,7 +286,7 @@ void RallyPointController::_updateContainsItems(void) bool RallyPointController::showPlanFromManagerVehicle (void) { - qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _editMode" << _editMode; + qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView; if (_masterController->offline()) { qCWarning(RallyPointControllerLog) << "RallyPointController::showPlanFromManagerVehicle called while offline"; return true; // stops further propagation of showPlanFromManagerVehicle due to error diff --git a/src/MissionManager/SectionTest.cc b/src/MissionManager/SectionTest.cc index bb226ad3e458ba768503b02fe94a32edeac92941..8a2a9a19deadffc76e6a16674870f901351838ba 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, true /* editMode */, missionItem); + _simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this); } void SectionTest::cleanup(void) @@ -77,13 +77,13 @@ 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, true /* editMode */, waypointItem); + SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, waypointItem, this); waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem); QmlObjectListModel complexVisualItems; - SurveyComplexItem surveyItem(_offlineVehicle); + SurveyComplexItem surveyItem(_offlineVehicle, false /* fly View */, this); complexVisualItems.append(&surveyItem); // This tests the common cases which should not lead to scan succeess diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index fd707e867724a80698c78c65e1b836cee57af4fe..e651a6fb4dfc72c89abdbf467ad246d7394d60d6 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -51,8 +51,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, }; -SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) - : VisualMissionItem (vehicle, parent) +SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) + : VisualMissionItem (vehicle, flyView, parent) , _rawEdit (false) , _dirty (false) , _ignoreDirtyChangeSignals (false) @@ -84,8 +84,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) setDirty(false); } -SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent) - : VisualMissionItem (vehicle, parent) +SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent) + : VisualMissionItem (vehicle, flyView, parent) , _missionItem (missionItem) , _rawEdit (false) , _dirty (false) @@ -130,13 +130,13 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss _altitudeFact.setRawValue(specifiesCoordinate() ? _missionItem._param7Fact.rawValue() : qQNaN()); _amslAltAboveTerrainFact.setRawValue(qQNaN()); - // In !editMode we skip some of the intialization to save memory - if (editMode) { + // In flyView we skip some of the intialization to save memory + if (!_flyView) { _setupMetaData(); } _connectSignals(); _updateOptionalSections(); - if (editMode) { + if (!_flyView) { _rebuildFacts(); } @@ -146,8 +146,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss setDirty(false); } -SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent) - : VisualMissionItem (other, parent) +SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent) + : VisualMissionItem (other, flyView, parent) , _missionItem (other._vehicle) , _rawEdit (false) , _dirty (false) diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index 96fed564b6894476ef573a539037b8ba280f4271..b172b14e5c0e2e8a8cd736b0f596238e2d9e2e22 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -23,9 +23,9 @@ class SimpleMissionItem : public VisualMissionItem Q_OBJECT public: - SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL); - SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent = NULL); - SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL); + SimpleMissionItem(Vehicle* vehicle, bool flyView, 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 7a91914b4751c3229a41462e3f78a269b5cce50e..3cef64fa51db0ee0df6f66ce02a60b5b73164282 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -92,7 +92,7 @@ void SimpleMissionItemTest::init(void) 70.1234567, true, // autoContinue false); // isCurrentItem - _simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); + _simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this); // 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 @@ -131,7 +131,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) 70.1234567, true, // autoContinue false); // isCurrentItem - SimpleMissionItem simpleMissionItem(vehicle, true /* editMode */, missionItem); + SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, NULL); // Validate that the fact values are correctly returned @@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) void SimpleMissionItemTest::_testDefaultValues(void) { - SimpleMissionItem item(_offlineVehicle); + SimpleMissionItem item(_offlineVehicle, false /* flyView */, NULL); item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT); item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); diff --git a/src/MissionManager/SpeedSectionTest.cc b/src/MissionManager/SpeedSectionTest.cc index b62db1c56fb6f7ddb48fc9b4b63550fffa1daff8..a52442c2761a6f2e069d3987d4439af2f34563f7 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, true /* editMode */, missionItem); + SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this); 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, true /* editMode */, validSpeedItem); + SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, NULL); MissionItem& simpleMissionItem = simpleItem.missionItem(); visualItems.append(&simpleItem); scanIndex = 0; @@ -263,9 +263,8 @@ void SpeedSectionTest::_testScanForSection(void) scanIndex = 0; // 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, true /* editMode */, waypointMissionItem); + SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, NULL); simpleMissionItem = validSpeedItem; visualItems.append(&simpleWaypointItem); visualItems.append(&simpleMissionItem); diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc index 3942ef5cc4aadcf6ff0fe9731ccca47774c05ca1..1b815d4dc5afc3d22413db4a0f8cd2257cb8c9d5 100644 --- a/src/MissionManager/StructureScanComplexItem.cc +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -31,8 +31,8 @@ const char* StructureScanComplexItem::_jsonAltitudeRelativeKey = "altitud QMap StructureScanComplexItem::_metaDataMap; -StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* parent) - : ComplexMissionItem (vehicle, parent) +StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent) + : ComplexMissionItem (vehicle, flyView, parent) , _sequenceNumber (0) , _dirty (false) , _altitudeRelative (true) diff --git a/src/MissionManager/StructureScanComplexItem.h b/src/MissionManager/StructureScanComplexItem.h index 8ebffef5139507c9ce314d745cb550b53b315e4b..3577abe0c37b64561a171520253ca2840f982af2 100644 --- a/src/MissionManager/StructureScanComplexItem.h +++ b/src/MissionManager/StructureScanComplexItem.h @@ -25,7 +25,7 @@ class StructureScanComplexItem : public ComplexMissionItem Q_OBJECT public: - StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); + StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent); Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT) Q_PROPERTY(Fact* altitude READ altitude CONSTANT) diff --git a/src/MissionManager/StructureScanComplexItemTest.cc b/src/MissionManager/StructureScanComplexItemTest.cc index 3a2a4081f5e5cc92294ce09d49df3ed3c706ce12..7f7280b335ccecd1c60e34cd371f818d791e17b1 100644 --- a/src/MissionManager/StructureScanComplexItemTest.cc +++ b/src/MissionManager/StructureScanComplexItemTest.cc @@ -24,7 +24,7 @@ void StructureScanComplexItemTest::init(void) _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool)); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); - _structureScanItem = new StructureScanComplexItem(_offlineVehicle, this); + _structureScanItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, this); _structureScanItem->setDirty(false); _multiSpy = new MultiSignalSpy(); @@ -121,7 +121,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void) _structureScanItem->save(items); QString errorString; - StructureScanComplexItem* newItem = new StructureScanComplexItem(_offlineVehicle, this); + StructureScanComplexItem* newItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, this); QVERIFY(newItem->load(items[0].toObject(), 10, errorString)); QVERIFY(errorString.isEmpty()); _validateItem(newItem); diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 78cf671273cf3a4d321973b31622b60734d4529f..92b3955b45bb3a5a1e0dae61c8712c8d894a8f11 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -58,8 +58,8 @@ const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedVa const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees"; -SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, QObject* parent) - : TransectStyleComplexItem (vehicle, settingsGroup, parent) +SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent) + : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this)) , _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName]) , _gridEntryLocationFact (settingsGroup, _metaDataMap[gridEntryLocationName]) diff --git a/src/MissionManager/SurveyComplexItem.h b/src/MissionManager/SurveyComplexItem.h index 36d5d8582c6d7236db834fba87247bf9c9ff1a0d..4e77a30724c7ed029b691c0fea95268e130367c0 100644 --- a/src/MissionManager/SurveyComplexItem.h +++ b/src/MissionManager/SurveyComplexItem.h @@ -21,7 +21,7 @@ class SurveyComplexItem : public TransectStyleComplexItem Q_OBJECT public: - SurveyComplexItem(Vehicle* vehicle, QObject* parent = NULL); + SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent); Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT) Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT) diff --git a/src/MissionManager/SurveyComplexItemTest.cc b/src/MissionManager/SurveyComplexItemTest.cc index e2fa78acd1fcf799db8c84b9cd74888727240142..10e0ea88e73d92fe9e6d59bff2b3b2f410bacbda 100644 --- a/src/MissionManager/SurveyComplexItemTest.cc +++ b/src/MissionManager/SurveyComplexItemTest.cc @@ -29,7 +29,7 @@ void SurveyComplexItemTest::init(void) _rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool)); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); - _surveyItem = new SurveyComplexItem(_offlineVehicle, this); + _surveyItem = new SurveyComplexItem(_offlineVehicle, false /* flyView */, this); _surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance _surveyItem->setDirty(false); _mapPolygon = _surveyItem->surveyAreaPolygon(); diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 0c3193e83effea3ba9335b0c38e39144dc4eafb1..ce0ad68bc31ef8d0e3101db9ddf8a92703c953d9 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -38,8 +38,8 @@ const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "Fol const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000; -TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent) - : ComplexMissionItem (vehicle, parent) +TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settingsGroup, QObject* parent) + : ComplexMissionItem (vehicle, flyView, parent) , _settingsGroup (settingsGroup) , _sequenceNumber (0) , _dirty (false) diff --git a/src/MissionManager/TransectStyleComplexItem.h b/src/MissionManager/TransectStyleComplexItem.h index 295b4416c9b6809eb9ccc232fbc919ec4eea170c..0b5bbf8f4d49892e4b6188590f3dc77770dcf866 100644 --- a/src/MissionManager/TransectStyleComplexItem.h +++ b/src/MissionManager/TransectStyleComplexItem.h @@ -25,7 +25,7 @@ class TransectStyleComplexItem : public ComplexMissionItem Q_OBJECT public: - TransectStyleComplexItem(Vehicle* vehicle, QString settignsGroup, QObject* parent = NULL); + TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settignsGroup, QObject* parent); Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT) Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT) diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc index e0925b50e0c312d83276970c0a998aadc453b1f2..a4c6b7543b82686a86e81113de9146810adef84c 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.cc +++ b/src/MissionManager/TransectStyleComplexItemTest.cc @@ -168,7 +168,7 @@ void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void) } TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent) - : TransectStyleComplexItem (vehicle, QStringLiteral("UnitTestTransect"), parent) + : TransectStyleComplexItem (vehicle, false /* flyView */, QStringLiteral("UnitTestTransect"), parent) , rebuildTransectsCalled (false) { diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc index 140b3c035644adae1219fcf8475cfb107c1ae137..37707d614749954549eec23a8c401226c3f44bea 100644 --- a/src/MissionManager/VisualMissionItem.cc +++ b/src/MissionManager/VisualMissionItem.cc @@ -21,9 +21,10 @@ const char* VisualMissionItem::jsonTypeKey = "type"; const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem"; const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem"; -VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) +VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) : QObject (parent) , _vehicle (vehicle) + , _flyView (flyView) , _isCurrentItem (false) , _dirty (false) , _homePositionSpecialCase (false) @@ -41,9 +42,10 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) _commonInit(); } -VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent) +VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent) : QObject (parent) , _vehicle (NULL) + , _flyView (flyView) , _isCurrentItem (false) , _dirty (false) , _homePositionSpecialCase (false) @@ -161,7 +163,7 @@ void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw) void VisualMissionItem::_updateTerrainAltitude(void) { - if (coordinate().isValid()) { + if (!_flyView && coordinate().isValid()) { // We use a timer so that any additional requests before the timer fires result in only a single request _updateTerrainTimer.start(); } diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h index 96cb4fc1a24c3cbd3c54a79fdba128cb71cc7a0a..21056a29dad206c099a6ca0926248fa953aa16a8 100644 --- a/src/MissionManager/VisualMissionItem.h +++ b/src/MissionManager/VisualMissionItem.h @@ -33,8 +33,8 @@ class VisualMissionItem : public QObject Q_OBJECT public: - VisualMissionItem(Vehicle* vehicle, QObject* parent = NULL); - VisualMissionItem(const VisualMissionItem& other, QObject* parent = NULL); + VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent); + VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent); ~VisualMissionItem(); @@ -189,6 +189,7 @@ signals: protected: Vehicle* _vehicle; + bool _flyView; bool _isCurrentItem; bool _dirty; bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 0b352354fc9ebb3ce902d6134f7f8c6929d3f8dc..268d2a406f2348d46a303ae703cf7b6b1febc660 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -157,7 +157,7 @@ QGCView { id: masterController Component.onCompleted: { - start(true /* editMode */) + start(false /* flyView */) _missionController.setCurrentPlanViewIndex(0, true) }