diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index ab54a7da11981d3f0d41bf89c6ebe1e1c2722bbd..c61eb2c2ab2620eb204158a35ceff6049073f44b 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -40,6 +40,8 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC _transactionInProgress = TransactionWrite; + _connectToMavlink(); + mavlink_message_t messageOut; mavlink_mission_item_t missionItem; diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index 4cbe7b2a02c60cd2872051fefba3177c779cb07f..b132c5228e97d0e3eb89fac46901374177edec89 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -38,7 +38,6 @@ PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType) _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds); connect(_ackTimeoutTimer, &QTimer::timeout, this, &PlanManager::_ackTimeout); - connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); } PlanManager::~PlanManager() @@ -63,6 +62,7 @@ void PlanManager::_writeMissionItemsWorker(void) _transactionInProgress = TransactionWrite; _retryCount = 0; emit inProgressChanged(true); + _connectToMavlink(); _writeMissionCount(); } @@ -139,6 +139,7 @@ void PlanManager::loadFromVehicle(void) _retryCount = 0; _transactionInProgress = TransactionRead; emit inProgressChanged(true); + _connectToMavlink(); _requestList(); } @@ -802,6 +803,7 @@ QString PlanManager::_missionResultToString(MAV_MISSION_RESULT result) void PlanManager::_finishTransaction(bool success) { emit progressPct(1); + _disconnectFromMavlink(); _itemIndicesToRead.clear(); _itemIndicesToWrite.clear(); @@ -890,6 +892,7 @@ void PlanManager::_removeAllWorker(void) emit progressPct(0); + _connectToMavlink(); _dedicatedLink = _vehicle->priorityLink(); mavlink_msg_mission_clear_all_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), @@ -941,6 +944,16 @@ void PlanManager::_clearAndDeleteWriteMissionItems(void) _writeMissionItems.clear(); } +void PlanManager::_connectToMavlink(void) +{ + connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); +} + +void PlanManager::_disconnectFromMavlink(void) +{ + disconnect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); +} + QString PlanManager::_planTypeString(void) { switch (_planType) { diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index 8633588e92d6649503cdb39b913cb4b9b0dc0a54..43f696c14ed9f7f6a8d5834c5cb311070a89e747 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -126,6 +126,8 @@ protected: void _clearAndDeleteWriteMissionItems(void); QString _lastMissionReqestString(MAV_MISSION_RESULT result); void _removeAllWorker(void); + void _connectToMavlink(void); + void _disconnectFromMavlink(void); QString _planTypeString(void); protected: