diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index a0d453646ac7491070248a16a68836c70adb5b87..a02ee1c5fe4f09b1a957507b93c5562cc44d2c16 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -33,22 +33,23 @@ const char* PlanMasterController::kJsonGeoFenceObjectKey = "geoFence"; const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints"; PlanMasterController::PlanMasterController(QObject* parent) - : QObject (parent) - , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) - , _controllerVehicle (new Vehicle( + : QObject (parent) + , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) + , _controllerVehicle (new Vehicle( static_cast(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()), static_cast(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) + , _managerVehicle (_controllerVehicle) + , _flyView (true) + , _offline (true) + , _missionController (this) + , _geoFenceController (this) + , _rallyPointController (this) + , _loadGeoFence (false) + , _loadRallyPoints (false) + , _sendGeoFence (false) + , _sendRallyPoints (false) + , _deleteWhenSendCompleted (false) { connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); @@ -86,9 +87,10 @@ void PlanMasterController::start(bool flyView) #endif } -void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle) +void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle, bool deleteWhenSendCompleted) { _flyView = true; + _deleteWhenSendCompleted = deleteWhenSendCompleted; _missionController.start(_flyView); _geoFenceController.start(_flyView); _rallyPointController.start(_flyView); @@ -264,6 +266,9 @@ void PlanMasterController::_sendGeoFenceComplete(void) void PlanMasterController::_sendRallyPointsComplete(void) { qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete"; + if (_deleteWhenSendCompleted) { + this->deleteLater(); + } } void PlanMasterController::sendToVehicle(void) @@ -535,10 +540,9 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi { // Use a transient PlanMasterController to accomplish this PlanMasterController* controller = new PlanMasterController(); - controller->startStaticActiveVehicle(vehicle); + controller->startStaticActiveVehicle(vehicle, true /* deleteWhenSendCompleted */); controller->loadFromFile(filename); controller->sendToVehicle(); - delete controller; } void PlanMasterController::_showPlanFromManagerVehicle(void) diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h index 8d38401d88f3a8653d164d72a7236bd9b8abf59c..b0df25926d95e0e544e2025ad5374de70d0cc6b0 100644 --- a/src/MissionManager/PlanMasterController.h +++ b/src/MissionManager/PlanMasterController.h @@ -49,7 +49,8 @@ public: 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); + /// @param deleteWhenSendCmplete The PlanMasterController object should be deleted after the first send is completed. + Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle, bool deleteWhenSendCompleted = false); /// Determines if the plan has all data needed to be saved or sent to the vehicle. Currently the only case where this /// would return false is when it is still waiting on terrain data to determine correct altitudes. @@ -127,5 +128,6 @@ private: bool _sendGeoFence; bool _sendRallyPoints; QString _currentPlanFile; + bool _deleteWhenSendCompleted; }; diff --git a/src/MissionManager/RallyPointController.cc b/src/MissionManager/RallyPointController.cc index 58a369aa4ece83d646c9a3e0d97b2a7980de33c9..589fb5f5d01fed770be28a3bc4a8292c915a59db 100644 --- a/src/MissionManager/RallyPointController.cc +++ b/src/MissionManager/RallyPointController.cc @@ -203,15 +203,15 @@ QString RallyPointController::editorQml(void) const return _rallyPointManager->editorQml(); } -void RallyPointController::_managerLoadComplete(const QList rgPoints) +void RallyPointController::_managerLoadComplete(void) { // Fly view always reloads on _loadComplete // Plan view only reloads on _loadComplete if specifically requested if (_flyView || _itemsRequested) { _points.clearAndDeleteContents(); QObjectList pointList; - for (int i=0; ipoints().count(); i++) { + pointList.append(new RallyPoint(_rallyPointManager->points()[i], this)); } _points.swapObjectList(pointList); setDirty(false); @@ -224,7 +224,7 @@ void RallyPointController::_managerLoadComplete(const QList rgPo void RallyPointController::_managerSendComplete(bool error) { // Fly view always reloads after send - if (!error && !_flyView) { + if (!error && _flyView) { showPlanFromManagerVehicle(); } } @@ -317,6 +317,7 @@ bool RallyPointController::showPlanFromManagerVehicle (void) } else { qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle: sync complete"; _itemsRequested = true; + _managerLoadComplete(); return false; } } diff --git a/src/MissionManager/RallyPointController.h b/src/MissionManager/RallyPointController.h index eff4b242ee2176b3b96bc8cd7982c3d79a5814ab..95d1f0f13b672c517b70d479730f6429fa071506 100644 --- a/src/MissionManager/RallyPointController.h +++ b/src/MissionManager/RallyPointController.h @@ -61,7 +61,7 @@ signals: void loadComplete(void); private slots: - void _managerLoadComplete(const QList rgPoints); + void _managerLoadComplete(void); void _managerSendComplete(bool error); void _managerRemoveAllComplete(bool error); void _setFirstPointCurrent(void); diff --git a/src/MissionManager/RallyPointManager.cc b/src/MissionManager/RallyPointManager.cc index e0880cae67856372387198b9cbc8e0d68f89d75e..0db0f7342c1a3633c315fa7c3c7dac869765b281 100644 --- a/src/MissionManager/RallyPointManager.cc +++ b/src/MissionManager/RallyPointManager.cc @@ -21,7 +21,7 @@ RallyPointManager::RallyPointManager(Vehicle* vehicle) connect(&_planManager, &PlanManager::inProgressChanged, this, &RallyPointManager::inProgressChanged); connect(&_planManager, &PlanManager::error, this, &RallyPointManager::error); connect(&_planManager, &PlanManager::removeAllComplete, this, &RallyPointManager::removeAllComplete); - connect(&_planManager, &PlanManager::sendComplete, this, &RallyPointManager::sendComplete); + connect(&_planManager, &PlanManager::sendComplete, this, &RallyPointManager::_sendComplete); connect(&_planManager, &PlanManager::newMissionItemsAvailable, this, &RallyPointManager::_planManagerLoadComplete); } @@ -45,8 +45,12 @@ void RallyPointManager::loadFromVehicle(void) void RallyPointManager::sendToVehicle(const QList& rgPoints) { - QList rallyItems; + _rgSendPoints.clear(); + for (const QGeoCoordinate& rallyPoint: rgPoints) { + _rgSendPoints.append(rallyPoint); + } + QList rallyItems; for (int i=0; i rgPoints); + void loadComplete (void); void inProgressChanged (bool inProgress); void error (int errorCode, const QString& errorMsg); void removeAllComplete (bool error); void sendComplete (bool error); private slots: + void _sendComplete (bool error); void _planManagerLoadComplete (bool removeAllRequested); protected: @@ -77,6 +78,7 @@ protected: Vehicle* _vehicle; PlanManager _planManager; QList _rgPoints; + QList _rgSendPoints; }; #endif