From b83e16a0b35f7d206759671c96031115e5429e41 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Sun, 17 Jun 2018 11:56:13 -0700 Subject: [PATCH] Fix sync indicator when Plan view waits for initial load complete --- src/MissionManager/MissionController.cc | 47 +++++++++++++--------- src/MissionManager/MissionController.h | 1 + src/MissionManager/PlanElementController.h | 1 - src/MissionManager/PlanManager.cc | 47 +++++++++++----------- src/MissionManager/PlanManager.h | 3 ++ src/MissionManager/PlanMasterController.cc | 45 +++++++++------------ src/MissionManager/PlanMasterController.h | 10 ++--- 7 files changed, 79 insertions(+), 75 deletions(-) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 572e0ca03..1f87f6f1e 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -54,20 +54,21 @@ const char* MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT"; const int MissionController::_missionFileVersion = 2; MissionController::MissionController(PlanMasterController* masterController, QObject *parent) - : PlanElementController(masterController, parent) - , _missionManager(_managerVehicle->missionManager()) - , _visualItems(NULL) - , _settingsItem(NULL) - , _firstItemsFromVehicle(false) - , _itemsRequested(false) - , _surveyMissionItemName(tr("Survey")) - , _fwLandingMissionItemName(tr("Fixed Wing Landing")) - , _structureScanMissionItemName(tr("Structure Scan")) - , _corridorScanMissionItemName(tr("Corridor Scan")) - , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings()) - , _progressPct(0) - , _currentPlanViewIndex(-1) - , _currentPlanViewItem(NULL) + : PlanElementController (masterController, parent) + , _missionManager (_managerVehicle->missionManager()) + , _visualItems (NULL) + , _settingsItem (NULL) + , _firstItemsFromVehicle (false) + , _itemsRequested (false) + , _inRecalcSequence (false) + , _surveyMissionItemName (tr("Survey")) + , _fwLandingMissionItemName (tr("Fixed Wing Landing")) + , _structureScanMissionItemName (tr("Structure Scan")) + , _corridorScanMissionItemName (tr("Corridor Scan")) + , _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings()) + , _progressPct (0) + , _currentPlanViewIndex (-1) + , _currentPlanViewItem (NULL) { _resetMissionFlightStatus(); managerVehicleChanged(_managerVehicle); @@ -142,17 +143,17 @@ void MissionController::_init(void) // Called when new mission items have completed downloading from Vehicle void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested) { - qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle"; + qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count(); // Fly view always reloads on _loadComplete // Plan view only reloads on _loadComplete if specifically requested - if (_flyView || removeAllRequested || _itemsRequested) { + if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) { // Fly Mode (accept if): // - Always accepts new items from the vehicle so Fly view is kept up to date // Edit Mode (accept if): - // - Either a load from vehicle was manually requested or + // - Remove all was requested from Fly view (clear mission on flight end) + // - A load from vehicle was manually requested // - The initial automatic load from a vehicle completed and the current editor is empty - // - Remove all way requested from Fly view (clear mission on flight end) QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this); const QList& newMissionItems = _missionManager->missionItems(); @@ -1481,15 +1482,21 @@ void MissionController::_recalcMissionFlightStatus() // This will update the sequence numbers to be sequential starting from 0 void MissionController::_recalcSequence(void) { + if (_inRecalcSequence) { + // Don't let this call recurse due to signalling + return; + } + // Setup ascending sequence numbers for all visual items + _inRecalcSequence = true; int sequenceNumber = 0; for (int i=0; i<_visualItems->count(); i++) { VisualMissionItem* item = qobject_cast(_visualItems->get(i)); - item->setSequenceNumber(sequenceNumber); sequenceNumber = item->lastSequenceNumber() + 1; - } + } + _inRecalcSequence = false; } // This will update the child item hierarchy diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 5015a95ae..4a2fda27c 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -267,6 +267,7 @@ private: CoordVectHashTable _linesTable; bool _firstItemsFromVehicle; bool _itemsRequested; + bool _inRecalcSequence; MissionFlightStatus_t _missionFlightStatus; QString _surveyMissionItemName; QString _fwLandingMissionItemName; diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index 0690c84be..078f218a2 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -63,7 +63,6 @@ signals: void containsItemsChanged (bool containsItems); void syncInProgressChanged (bool syncInProgress); void dirtyChanged (bool dirty); - void vehicleChanged (Vehicle* vehicle); void sendComplete (void); void removeAllComplete (void); diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index bd51e3702..6ec82d3df 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -22,17 +22,17 @@ QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog") PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType) - : _vehicle(vehicle) - , _planType(planType) - , _dedicatedLink(NULL) - , _ackTimeoutTimer(NULL) - , _expectedAck(AckNone) - , _transactionInProgress(TransactionNone) - , _resumeMission(false) - , _lastMissionRequest(-1) - , _missionItemCountToRead(-1) - , _currentMissionIndex(-1) - , _lastCurrentIndex(-1) + : _vehicle (vehicle) + , _planType (planType) + , _dedicatedLink (NULL) + , _ackTimeoutTimer (NULL) + , _expectedAck (AckNone) + , _transactionInProgress (TransactionNone) + , _resumeMission (false) + , _lastMissionRequest (-1) + , _missionItemCountToRead (-1) + , _currentMissionIndex (-1) + , _lastCurrentIndex (-1) { _ackTimeoutTimer = new QTimer(this); _ackTimeoutTimer->setSingleShot(true); @@ -59,9 +59,8 @@ void PlanManager::_writeMissionItemsWorker(void) _itemIndicesToWrite << i; } - _transactionInProgress = TransactionWrite; _retryCount = 0; - emit inProgressChanged(true); + _setTransactionInProgress(TransactionWrite); _connectToMavlink(); _writeMissionCount(); } @@ -137,8 +136,7 @@ void PlanManager::loadFromVehicle(void) } _retryCount = 0; - _transactionInProgress = TransactionRead; - emit inProgressChanged(true); + _setTransactionInProgress(TransactionRead); _connectToMavlink(); _requestList(); } @@ -822,12 +820,7 @@ void PlanManager::_finishTransaction(bool success, bool apmGuidedItemWrite) // First thing we do is clear the transaction. This way inProgesss is off when we signal transaction complete. TransactionType_t currentTransactionType = _transactionInProgress; - _transactionInProgress = TransactionNone; - if (currentTransactionType != TransactionNone) { - _transactionInProgress = TransactionNone; - qCDebug(PlanManagerLog) << QStringLiteral("inProgressChanged %1").arg(_planTypeString()); - emit inProgressChanged(false); - } + _setTransactionInProgress(TransactionNone); switch (currentTransactionType) { case TransactionRead: @@ -920,9 +913,8 @@ void PlanManager::removeAll(void) emit lastCurrentIndexChanged(-1); } - _transactionInProgress = TransactionRemoveAll; _retryCount = 0; - emit inProgressChanged(true); + _setTransactionInProgress(TransactionRemoveAll); _removeAllWorker(); } @@ -970,3 +962,12 @@ QString PlanManager::_planTypeString(void) return QStringLiteral("T:Unknown"); } } + +void PlanManager::_setTransactionInProgress(TransactionType_t type) +{ + if (_transactionInProgress != type) { + qCDebug(PlanManagerLog) << "_setTransactionInProgress" << _planTypeString() << type; + _transactionInProgress = type; + emit inProgressChanged(inProgress()); + } +} diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index b5c53b52a..caa6173a0 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -153,6 +153,9 @@ protected: QList _writeMissionItems; ///< Set of mission items currently being written to vehicle int _currentMissionIndex; int _lastCurrentIndex; + +private: + void _setTransactionInProgress(TransactionType_t type); }; #endif diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index 48b331a79..ebaeab53b 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -42,7 +42,6 @@ PlanMasterController::PlanMasterController(QObject* parent) , _loadRallyPoints (false) , _sendGeoFence (false) , _sendRallyPoints (false) - , _syncInProgress (false) { connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); @@ -123,15 +122,18 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) connect(_managerVehicle->geoFenceManager(), &GeoFenceManager::sendComplete, this, &PlanMasterController::_sendGeoFenceComplete); connect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete); } - if (newOffline != _offline) { - _offline = newOffline; - emit offlineEditingChanged(newOffline); - } _missionController.managerVehicleChanged(_managerVehicle); _geoFenceController.managerVehicleChanged(_managerVehicle); _rallyPointController.managerVehicleChanged(_managerVehicle); + // Vehicle changed so we need to signal everything + _offline = newOffline; + emit containsItemsChanged(containsItems()); + emit syncInProgressChanged(); + emit dirtyChanged(dirty()); + emit offlineChanged(offline()); + if (!_flyView) { if (!offline()) { // We are in Plan view and we have a newly connected vehicle: @@ -170,9 +172,7 @@ void PlanMasterController::loadFromVehicle(void) qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while syncInProgress"; } else { _loadGeoFence = true; - _syncInProgress = true; - emit syncInProgressChanged(true); - qCDebug(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle _missionController.loadFromVehicle"; + qCDebug(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle calling _missionController.loadFromVehicle"; _missionController.loadFromVehicle(); setDirty(false); } @@ -185,7 +185,7 @@ void PlanMasterController::_loadMissionComplete(void) _loadGeoFence = false; _loadRallyPoints = true; if (_geoFenceController.supported()) { - qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete _geoFenceController.loadFromVehicle"; + qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete calling _geoFenceController.loadFromVehicle"; _geoFenceController.loadFromVehicle(); } else { qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete GeoFence not supported skipping"; @@ -201,7 +201,7 @@ void PlanMasterController::_loadGeoFenceComplete(void) if (!_flyView && _loadRallyPoints) { _loadRallyPoints = false; if (_rallyPointController.supported()) { - qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle"; + qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete calling _rallyPointController.loadFromVehicle"; _rallyPointController.loadFromVehicle(); } else { qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete Rally Points not supported skipping"; @@ -214,10 +214,7 @@ void PlanMasterController::_loadGeoFenceComplete(void) void PlanMasterController::_loadRallyPointsComplete(void) { - if (!_flyView) { - _syncInProgress = false; - emit syncInProgressChanged(false); - } + qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadRallyPointsComplete"; } void PlanMasterController::_sendMissionComplete(void) @@ -252,11 +249,7 @@ void PlanMasterController::_sendGeoFenceComplete(void) void PlanMasterController::_sendRallyPointsComplete(void) { - if (_syncInProgress) { - qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete"; - _syncInProgress = false; - emit syncInProgressChanged(false); - } + qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete"; } void PlanMasterController::sendToVehicle(void) @@ -273,8 +266,6 @@ void PlanMasterController::sendToVehicle(void) } else { qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start mission sendToVehicle"; _sendGeoFence = true; - _syncInProgress = true; - emit syncInProgressChanged(true); _missionController.sendToVehicle(); setDirty(false); } @@ -504,10 +495,7 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi void PlanMasterController::_showPlanFromManagerVehicle(void) { - if (!_managerVehicle->initialPlanRequestComplete() && - !_missionController.syncInProgress() && - !_geoFenceController.syncInProgress() && - !_rallyPointController.syncInProgress()) { + if (!_managerVehicle->initialPlanRequestComplete() && !syncInProgress()) { // Something went wrong with initial load. All controllers are idle, so just force it off _managerVehicle->forceInitialPlanRequestComplete(); } @@ -519,3 +507,10 @@ void PlanMasterController::_showPlanFromManagerVehicle(void) } } } + +bool PlanMasterController::syncInProgress(void) const +{ + return _missionController.syncInProgress() || + _geoFenceController.syncInProgress() || + _rallyPointController.syncInProgress(); +} diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h index d6d454fa8..896349433 100644 --- a/src/MissionManager/PlanMasterController.h +++ b/src/MissionManager/PlanMasterController.h @@ -34,7 +34,7 @@ public: Q_PROPERTY(RallyPointController* rallyPointController READ rallyPointController CONSTANT) Q_PROPERTY(Vehicle* controllerVehicle MEMBER _controllerVehicle CONSTANT) - Q_PROPERTY(bool offline READ offline NOTIFY offlineEditingChanged) ///< true: controller is not connected to an active vehicle + Q_PROPERTY(bool offline READ offline NOTIFY offlineChanged) ///< true: controller is not connected to an active vehicle Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: Information is currently being saved/sent, false: no active save/send in progress Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: Unsaved/sent changes are present, false: no changes since last save/send @@ -74,7 +74,7 @@ public: bool offline (void) const { return _offline; } bool containsItems (void) const; - bool syncInProgress (void) const { return _syncInProgress; } + bool syncInProgress (void) const; bool dirty (void) const; void setDirty (bool dirty); QString fileExtension (void) const; @@ -90,10 +90,9 @@ public: signals: void containsItemsChanged (bool containsItems); - void syncInProgressChanged (bool syncInProgress); + void syncInProgressChanged (void); void dirtyChanged (bool dirty); - void vehicleChanged (Vehicle* vehicle); - void offlineEditingChanged (bool offlineEditing); + void offlineChanged (bool offlineEditing); private slots: void _activeVehicleChanged(Vehicle* activeVehicle); @@ -119,7 +118,6 @@ private: bool _loadRallyPoints; bool _sendGeoFence; bool _sendRallyPoints; - bool _syncInProgress; static const int _planFileVersion; static const char* _planFileType; -- 2.22.0