Browse Source

Revert "Fix current mission item updates"

QGC4.4
Don Gagne 8 years ago committed by GitHub
parent
commit
82187dee79
  1. 2
      src/MissionManager/MissionManager.cc
  2. 15
      src/MissionManager/PlanManager.cc
  3. 2
      src/MissionManager/PlanManager.h

2
src/MissionManager/MissionManager.cc

@ -40,6 +40,8 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC @@ -40,6 +40,8 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
_transactionInProgress = TransactionWrite;
_connectToMavlink();
mavlink_message_t messageOut;
mavlink_mission_item_t missionItem;

15
src/MissionManager/PlanManager.cc

@ -38,7 +38,6 @@ PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType) @@ -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) @@ -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) @@ -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) @@ -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) @@ -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) @@ -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) {

2
src/MissionManager/PlanManager.h

@ -126,6 +126,8 @@ protected: @@ -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:

Loading…
Cancel
Save