Browse Source

Correct single transaction checking

QGC4.4
Don Gagne 9 years ago
parent
commit
9ccb906b1c
  1. 15
      src/MissionManager/MissionManager.cc

15
src/MissionManager/MissionManager.cc

@ -44,6 +44,11 @@ MissionManager::~MissionManager()
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
{ {
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
return;
}
bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle(); bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
_missionItems.clear(); _missionItems.clear();
@ -68,11 +73,6 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count(); qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
if (inProgress()) {
qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
return;
}
// Prime write list // Prime write list
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_missionItems.count(); i++) {
_itemIndicesToWrite << i; _itemIndicesToWrite << i;
@ -133,6 +133,11 @@ void MissionManager::requestMissionItems(void)
{ {
qCDebug(MissionManagerLog) << "requestMissionItems read sequence"; qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
if (inProgress()) {
qCDebug(MissionManagerLog) << "requestMissionItems called while transaction in progress";
return;
}
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_request_list_t request; mavlink_mission_request_list_t request;

Loading…
Cancel
Save