MissionManager.cc 21.1 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

Don Gagne's avatar
Don Gagne committed
10 11 12 13 14 15

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "MissionManager.h"
#include "Vehicle.h"
16
#include "FirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
17
#include "MAVLinkProtocol.h"
18
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
19 20 21 22

QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")

MissionManager::MissionManager(Vehicle* vehicle)
23
    : _vehicle(vehicle)
24
    , _dedicatedLink(NULL)
Don Gagne's avatar
Don Gagne committed
25 26
    , _ackTimeoutTimer(NULL)
    , _retryAck(AckNone)
27 28
    , _readTransactionInProgress(false)
    , _writeTransactionInProgress(false)
29
    , _currentMissionItem(-1)
Don Gagne's avatar
Don Gagne committed
30 31 32 33 34 35 36 37 38 39
{
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
    
    _ackTimeoutTimer = new QTimer(this);
    _ackTimeoutTimer->setSingleShot(true);
    _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
    
    connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
}

40
MissionManager::~MissionManager()
Don Gagne's avatar
Don Gagne committed
41
{
42

Don Gagne's avatar
Don Gagne committed
43 44
}

45
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
Don Gagne's avatar
Don Gagne committed
46
{
47 48
    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();

Don Gagne's avatar
Don Gagne committed
49
    _missionItems.clear();
50 51

    int firstIndex = skipFirstItem ? 1 : 0;
Don Gagne's avatar
Don Gagne committed
52
    
53
    for (int i=firstIndex; i<missionItems.count(); i++) {
54 55
        MissionItem* item = new MissionItem(*missionItems[i]);
        _missionItems.append(item);
56

57
        item->setIsCurrentItem(i == firstIndex);
58

59
        if (skipFirstItem) {
60
            // Home is in sequence 0, remainder of items start at sequence 1
61
            item->setSequenceNumber(item->sequenceNumber() - 1);
Don Gagne's avatar
Don Gagne committed
62
            if (item->command() == MAV_CMD_DO_JUMP) {
63 64
                item->setParam1((int)item->param1() - 1);
            }
Don Gagne's avatar
Don Gagne committed
65 66
        }
    }
67
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
68

69 70 71 72 73 74
    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
    
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
        return;
    }
Don Gagne's avatar
Don Gagne committed
75

76 77 78 79 80 81
    // Prime write list
    for (int i=0; i<_missionItems.count(); i++) {
        _itemIndicesToWrite << i;
    }
    _writeTransactionInProgress = true;

82 83
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
84

85 86 87
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
88

89
    mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount);
90

91 92
    _dedicatedLink = _vehicle->priorityLink();
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
93
    _startAckTimeout(AckMissionRequest);
94
    emit inProgressChanged(true);
95 96
}

Don Gagne's avatar
Don Gagne committed
97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131
void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly)
{
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeArduPilotGuidedMissionItem called while transaction in progress";
        return;
    }

    _writeTransactionInProgress = true;

    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;

    missionItem.target_system =     _vehicle->id();
    missionItem.target_component =  0;
    missionItem.seq =               0;
    missionItem.command =           MAV_CMD_NAV_WAYPOINT;
    missionItem.param1 =            0;
    missionItem.param2 =            0;
    missionItem.param3 =            0;
    missionItem.param4 =            0;
    missionItem.x =                 gotoCoord.latitude();
    missionItem.y =                 gotoCoord.longitude();
    missionItem.z =                 gotoCoord.altitude();
    missionItem.frame =             MAV_FRAME_GLOBAL_RELATIVE_ALT;
    missionItem.current =           altChangeOnly ? 3 : 2;
    missionItem.autocontinue =      true;

    mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem);

    _dedicatedLink = _vehicle->priorityLink();
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
    _startAckTimeout(AckGuidedItem);
    emit inProgressChanged(true);
}

132
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
133
{
Don Gagne's avatar
Don Gagne committed
134
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
Don Gagne's avatar
Don Gagne committed
135 136 137 138
    
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
    
139 140 141
    _requestItemRetryCount = 0;
    _itemIndicesToRead.clear();
    _readTransactionInProgress = true;
Don Gagne's avatar
Don Gagne committed
142 143 144 145 146
    _clearMissionItems();
    
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
    
147
    mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request);
Don Gagne's avatar
Don Gagne committed
148
    
149 150
    _dedicatedLink = _vehicle->priorityLink();
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
151 152 153 154
    _startAckTimeout(AckMissionCount);
    emit inProgressChanged(true);
}

Don Gagne's avatar
Don Gagne committed
155 156
void MissionManager::_ackTimeout(void)
{
157 158 159 160 161
    AckType_t timedOutAck = _retryAck;
    
    _retryAck = AckNone;
    
    if (timedOutAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
162
        qCWarning(MissionManagerLog) << "_ackTimeout timeout with AckNone";
163
        _sendError(InternalError, "Internal error occured during Mission Item communication: _ackTimeOut:_retryAck == AckNone");
Don Gagne's avatar
Don Gagne committed
164 165 166
        return;
    }
    
167 168
    _sendError(AckTimeoutError, QString("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(timedOutAck)));
    _finishTransaction(false);
Don Gagne's avatar
Don Gagne committed
169 170
}

171
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
172 173 174 175 176 177 178
{
    _retryAck = ack;
    _ackTimeoutTimer->start();
}

bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
{
179 180 181 182
    bool        success = false;
    AckType_t   savedRetryAck = _retryAck;
    
    _retryAck = AckNone;
Don Gagne's avatar
Don Gagne committed
183 184 185
    
    _ackTimeoutTimer->stop();
    
186
    if (savedRetryAck != expectedAck) {
187 188
        _sendError(ProtocolOrderError, QString("Vehicle responded incorrectly to mission item protocol sequence: %1:%2").arg(_ackTypeToString(savedRetryAck)).arg(_ackTypeToString(expectedAck)));
        _finishTransaction(false);
Don Gagne's avatar
Don Gagne committed
189 190 191 192 193 194 195 196
        success = false;
    } else {
        success = true;
    }
    
    return success;
}

197
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
198
{
199
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
200 201 202 203 204 205 206 207
    
    mavlink_message_t       message;
    mavlink_mission_ack_t   missionAck;
    
    missionAck.target_system =      _vehicle->id();
    missionAck.target_component =   MAV_COMP_ID_MISSIONPLANNER;
    missionAck.type =               MAV_MISSION_ACCEPTED;
    
208
    mavlink_msg_mission_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionAck);
Don Gagne's avatar
Don Gagne committed
209
    
210 211
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

212
    _finishTransaction(true);
Don Gagne's avatar
Don Gagne committed
213
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
214 215 216 217 218 219 220 221 222 223 224
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
    if (!_stopAckTimeout(AckMissionCount)) {
        return;
    }
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
225 226 227
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << missionCount.count;

    if (missionCount.count == 0) {
228
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
229
    } else {
230 231 232 233 234
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
235 236 237
    }
}

238
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
239
{
240 241 242 243
    qCDebug(MissionManagerLog) << "_requestNextMissionItem sequenceNumber:" << _itemIndicesToRead[0];

    if (_itemIndicesToRead.count() == 0) {
        _sendError(InternalError, "Internal Error: Call to Vehicle _requestNextMissionItem with no more indices to read");
Don Gagne's avatar
Don Gagne committed
244 245 246 247 248 249 250 251
        return;
    }
    
    mavlink_message_t           message;
    mavlink_mission_request_t   missionRequest;
    
    missionRequest.target_system =      _vehicle->id();
    missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
252
    missionRequest.seq =                _itemIndicesToRead[0];
Don Gagne's avatar
Don Gagne committed
253
    
254
    mavlink_msg_mission_request_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionRequest);
Don Gagne's avatar
Don Gagne committed
255
    
256
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
257
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
258 259 260 261 262 263 264 265 266 267 268 269 270 271
}

void MissionManager::_handleMissionItem(const mavlink_message_t& message)
{
    mavlink_mission_item_t missionItem;
    
    if (!_stopAckTimeout(AckMissionItem)) {
        return;
    }
    
    mavlink_msg_mission_item_decode(&message, &missionItem);
    
    qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << missionItem.seq;
    
272 273 274 275
    if (_itemIndicesToRead.contains(missionItem.seq)) {
        _requestItemRetryCount = 0;
        _itemIndicesToRead.removeOne(missionItem.seq);

276
        MissionItem* item = new MissionItem(missionItem.seq,
277 278 279 280 281 282 283 284 285 286 287 288
                                            (MAV_CMD)missionItem.command,
                                            (MAV_FRAME)missionItem.frame,
                                            missionItem.param1,
                                            missionItem.param2,
                                            missionItem.param3,
                                            missionItem.param4,
                                            missionItem.x,
                                            missionItem.y,
                                            missionItem.z,
                                            missionItem.autocontinue,
                                            missionItem.current,
                                            this);
Don Gagne's avatar
Don Gagne committed
289

Don Gagne's avatar
Don Gagne committed
290
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
291 292 293 294
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

295 296 297 298 299 300 301
        _missionItems.append(item);
    } else {
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << missionItem.seq;
        if (++_requestItemRetryCount > _maxRetryCount) {
            _sendError(RequestRangeError, QString("Vehicle would not send item %1 after max retries. Read from Vehicle failed.").arg(_itemIndicesToRead[0]));
            _finishTransaction(false);
            return;
302
        }
Don Gagne's avatar
Don Gagne committed
303
    }
304 305
    
    if (_itemIndicesToRead.count() == 0) {
306
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
307
    } else {
308
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
309 310 311 312 313
    }
}

void MissionManager::_clearMissionItems(void)
{
314
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
315 316 317 318 319 320 321 322 323 324 325 326 327 328 329
    _missionItems.clear();
}

void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
{
    mavlink_mission_request_t missionRequest;
    
    if (!_stopAckTimeout(AckMissionRequest)) {
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
    
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq;
    
330 331 332 333 334 335 336
    if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
        if (missionRequest.seq > _missionItems.count()) {
            _sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_missionItems.count()).arg(missionRequest.seq));
            _finishTransaction(false);
            return;
        } else {
            qCDebug(MissionManagerLog) << "_handleMissionRequest sequence number requested which has already been sent, sending again:" << missionRequest.seq;
337
        }
338 339
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
340 341 342 343 344
    }
    
    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;
    
345
    MissionItem* item = _missionItems[missionRequest.seq];
Don Gagne's avatar
Don Gagne committed
346 347 348 349 350 351 352 353 354
    
    missionItem.target_system =     _vehicle->id();
    missionItem.target_component =  MAV_COMP_ID_MISSIONPLANNER;
    missionItem.seq =               missionRequest.seq;
    missionItem.command =           item->command();
    missionItem.param1 =            item->param1();
    missionItem.param2 =            item->param2();
    missionItem.param3 =            item->param3();
    missionItem.param4 =            item->param4();
355 356 357
    missionItem.x =                 item->param5();
    missionItem.y =                 item->param6();
    missionItem.z =                 item->param7();
Don Gagne's avatar
Don Gagne committed
358 359 360 361
    missionItem.frame =             item->frame();
    missionItem.current =           missionRequest.seq == 0;
    missionItem.autocontinue =      item->autoContinue();
    
362
    mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem);
Don Gagne's avatar
Don Gagne committed
363
    
364
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
365
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
366 367 368 369 370 371
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
DonLakeFlyer's avatar
DonLakeFlyer committed
372
    // Save the retry ack before calling _stopAckTimeout since we'll need it to determine what
373 374 375 376 377 378 379
    // type of a protocol sequence we are in.
    AckType_t savedRetryAck = _retryAck;
    
    // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
    // a protocol sequence error. Call _stopAckTimeout with _retryAck so it will succeed no
    // matter what.
    if (!_stopAckTimeout(_retryAck)) {
Don Gagne's avatar
Don Gagne committed
380 381 382 383 384
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
385
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
386 387 388 389

    switch (savedRetryAck) {
        case AckNone:
            // State machine is idle. Vehicle is confused.
Don Gagne's avatar
Don Gagne committed
390
            _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
391 392 393
            break;
        case AckMissionCount:
            // MISSION_COUNT message expected
394 395
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
396 397 398
            break;
        case AckMissionItem:
            // MISSION_ITEM expected
399 400
            _sendError(VehicleError, QString("Vehicle returned error: %1. Partial list of mission items may have been returned.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
401 402 403 404
            break;
        case AckMissionRequest:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
405
                if (_itemIndicesToWrite.count() == 0) {
406
                    qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
407
                    _finishTransaction(true);
408
                } else {
409 410
                    _sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence, missed count %1. Vehicle only has partial list of mission items.").arg(_itemIndicesToWrite.count()));
                    _finishTransaction(false);
411 412
                }
            } else {
413 414
                _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
                _finishTransaction(false);
415 416
            }
            break;
Don Gagne's avatar
Don Gagne committed
417 418 419 420 421 422 423 424 425 426
        case AckGuidedItem:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
                qCDebug(MissionManagerLog) << "_handleMissionAck guide mode item accepted";
                _finishTransaction(true);
            } else {
                _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle did not accept guided item.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
                _finishTransaction(false);
            }
            break;
Don Gagne's avatar
Don Gagne committed
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454
    }
}

/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
        case MAVLINK_MSG_ID_MISSION_COUNT:
            _handleMissionCount(message);
            break;

        case MAVLINK_MSG_ID_MISSION_ITEM:
            _handleMissionItem(message);
            break;
            
        case MAVLINK_MSG_ID_MISSION_REQUEST:
            _handleMissionRequest(message);
            break;
            
        case MAVLINK_MSG_ID_MISSION_ACK:
            _handleMissionAck(message);
            break;
            
        case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
            // FIXME: NYI
            break;
            
        case MAVLINK_MSG_ID_MISSION_CURRENT:
455
            _handleMissionCurrent(message);
Don Gagne's avatar
Don Gagne committed
456 457 458 459
            break;
    }
}

460 461
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
462
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
463

464
    emit error(errorCode, errorMsg);
465
}
Don Gagne's avatar
Don Gagne committed
466 467 468 469

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
Don Gagne's avatar
Don Gagne committed
470
        case AckNone:
Don Gagne's avatar
Don Gagne committed
471
            return QString("No Ack");
Don Gagne's avatar
Don Gagne committed
472
        case AckMissionCount:
Don Gagne's avatar
Don Gagne committed
473
            return QString("MISSION_COUNT");
Don Gagne's avatar
Don Gagne committed
474
        case AckMissionItem:
Don Gagne's avatar
Don Gagne committed
475
            return QString("MISSION_ITEM");
Don Gagne's avatar
Don Gagne committed
476
        case AckMissionRequest:
Don Gagne's avatar
Don Gagne committed
477
            return QString("MISSION_REQUEST");
Don Gagne's avatar
Don Gagne committed
478 479
        case AckGuidedItem:
            return QString("Guided Mode Item");
Don Gagne's avatar
Don Gagne committed
480 481
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
482
            return QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
483
    }    
Don Gagne's avatar
Don Gagne committed
484
}
Don Gagne's avatar
Don Gagne committed
485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537

QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
    switch (result) {
        case MAV_MISSION_ACCEPTED:
            return QString("Mission accepted (MAV_MISSION_ACCEPTED)");
            break;
        case MAV_MISSION_ERROR:
            return QString("Unspecified error (MAV_MISSION_ERROR)");
            break;
        case MAV_MISSION_UNSUPPORTED_FRAME:
            return QString("Coordinate frame is not supported (MAV_MISSION_UNSUPPORTED_FRAME)");
            break;
        case MAV_MISSION_UNSUPPORTED:
            return QString("Command is not supported (MAV_MISSION_UNSUPPORTED)");
            break;
        case MAV_MISSION_NO_SPACE:
            return QString("Mission item exceeds storage space (MAV_MISSION_NO_SPACE)");
            break;
        case MAV_MISSION_INVALID:
            return QString("One of the parameters has an invalid value (MAV_MISSION_INVALID)");
            break;
        case MAV_MISSION_INVALID_PARAM1:
            return QString("Param1 has an invalid value (MAV_MISSION_INVALID_PARAM1)");
            break;
        case MAV_MISSION_INVALID_PARAM2:
            return QString("Param2 has an invalid value (MAV_MISSION_INVALID_PARAM2)");
            break;
        case MAV_MISSION_INVALID_PARAM3:
            return QString("param3 has an invalid value (MAV_MISSION_INVALID_PARAM3)");
            break;
        case MAV_MISSION_INVALID_PARAM4:
            return QString("Param4 has an invalid value (MAV_MISSION_INVALID_PARAM4)");
            break;
        case MAV_MISSION_INVALID_PARAM5_X:
            return QString("X/Param5 has an invalid value (MAV_MISSION_INVALID_PARAM5_X)");
            break;
        case MAV_MISSION_INVALID_PARAM6_Y:
            return QString("Y/Param6 has an invalid value (MAV_MISSION_INVALID_PARAM6_Y)");
            break;
        case MAV_MISSION_INVALID_PARAM7:
            return QString("Param7 has an invalid value (MAV_MISSION_INVALID_PARAM7)");
            break;
        case MAV_MISSION_INVALID_SEQUENCE:
            return QString("Received mission item out of sequence (MAV_MISSION_INVALID_SEQUENCE)");
            break;
        case MAV_MISSION_DENIED:
            return QString("Not accepting any mission commands (MAV_MISSION_DENIED)");
            break;
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
            return QString("QGC Internal Error");
    }
538
}
539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559

void MissionManager::_finishTransaction(bool success)
{
    if (!success && _readTransactionInProgress) {
        // Read from vehicle failed, clear partial list
        _missionItems.clear();
        emit newMissionItemsAvailable();
    }

    _readTransactionInProgress = false;
    _writeTransactionInProgress = false;
    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

    emit inProgressChanged(false);
}

bool MissionManager::inProgress(void)
{
    return _readTransactionInProgress || _writeTransactionInProgress;
}
560 561 562 563 564 565 566 567 568 569 570 571 572

void MissionManager::_handleMissionCurrent(const mavlink_message_t& message)
{
    mavlink_mission_current_t missionCurrent;

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

    qCDebug(MissionManagerLog) << "_handleMissionCurrent seq:" << missionCurrent.seq;
    if (missionCurrent.seq != _currentMissionItem) {
        _currentMissionItem = missionCurrent.seq;
        emit currentItemChanged(_currentMissionItem);
    }
}