MissionManager.cc 22.9 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 49 50
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

51 52 53 54 55
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
        return;
    }

56 57
    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();

Don Gagne's avatar
Don Gagne committed
58
    _missionItems.clear();
59 60

    int firstIndex = skipFirstItem ? 1 : 0;
Don Gagne's avatar
Don Gagne committed
61
    
62
    for (int i=firstIndex; i<missionItems.count(); i++) {
63 64
        MissionItem* item = new MissionItem(*missionItems[i]);
        _missionItems.append(item);
65

66
        item->setIsCurrentItem(i == firstIndex);
67

68
        if (skipFirstItem) {
69
            // Home is in sequence 0, remainder of items start at sequence 1
70
            item->setSequenceNumber(item->sequenceNumber() - 1);
Don Gagne's avatar
Don Gagne committed
71
            if (item->command() == MAV_CMD_DO_JUMP) {
72 73
                item->setParam1((int)item->param1() - 1);
            }
Don Gagne's avatar
Don Gagne committed
74 75
        }
    }
76
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
77

78 79
    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
    
80 81 82 83 84 85
    // Prime write list
    for (int i=0; i<_missionItems.count(); i++) {
        _itemIndicesToWrite << i;
    }
    _writeTransactionInProgress = true;

86 87
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
88

89 90 91
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
92

93
    _dedicatedLink = _vehicle->priorityLink();
94 95 96 97 98 99
    mavlink_msg_mission_count_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                          qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                          _dedicatedLink->mavlinkChannel(),
                                          &message,
                                          &missionCount);

100
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
101
    _startAckTimeout(AckMissionRequest);
102
    emit inProgressChanged(true);
103 104
}

Don Gagne's avatar
Don Gagne committed
105 106 107 108 109 110 111 112 113 114 115 116 117
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();
118
    missionItem.target_component =  _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
119 120 121 122 123 124 125 126 127 128 129 130 131 132
    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;

    _dedicatedLink = _vehicle->priorityLink();
133 134 135 136 137 138
    mavlink_msg_mission_item_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                         qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                         _dedicatedLink->mavlinkChannel(),
                                         &messageOut,
                                         &missionItem);

Don Gagne's avatar
Don Gagne committed
139 140 141 142 143
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
    _startAckTimeout(AckGuidedItem);
    emit inProgressChanged(true);
}

144
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
145
{
146 147 148 149
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
150
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
151 152 153 154 155

    if (inProgress()) {
        qCDebug(MissionManagerLog) << "requestMissionItems called while transaction in progress";
        return;
    }
Don Gagne's avatar
Don Gagne committed
156 157 158 159
    
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
    
160 161 162
    _requestItemRetryCount = 0;
    _itemIndicesToRead.clear();
    _readTransactionInProgress = true;
Don Gagne's avatar
Don Gagne committed
163 164 165 166 167
    _clearMissionItems();
    
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
    
168
    _dedicatedLink = _vehicle->priorityLink();
169 170 171 172 173 174
    mavlink_msg_mission_request_list_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                 qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                 _dedicatedLink->mavlinkChannel(),
                                                 &message,
                                                 &request);
    
175
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
176 177 178 179
    _startAckTimeout(AckMissionCount);
    emit inProgressChanged(true);
}

Don Gagne's avatar
Don Gagne committed
180 181
void MissionManager::_ackTimeout(void)
{
182 183 184 185 186
    AckType_t timedOutAck = _retryAck;
    
    _retryAck = AckNone;
    
    if (timedOutAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
187
        qCWarning(MissionManagerLog) << "_ackTimeout timeout with AckNone";
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
188
        _sendError(InternalError, "Internal error occurred during Mission Item communication: _ackTimeOut:_retryAck == AckNone");
Don Gagne's avatar
Don Gagne committed
189 190 191
        return;
    }
    
192 193
    _sendError(AckTimeoutError, QString("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(timedOutAck)));
    _finishTransaction(false);
Don Gagne's avatar
Don Gagne committed
194 195
}

196
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
197 198 199 200 201 202 203
{
    _retryAck = ack;
    _ackTimeoutTimer->start();
}

bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
{
204 205 206 207
    bool        success = false;
    AckType_t   savedRetryAck = _retryAck;
    
    _retryAck = AckNone;
Don Gagne's avatar
Don Gagne committed
208 209 210
    
    _ackTimeoutTimer->stop();
    
211
    if (savedRetryAck != expectedAck) {
212 213 214 215 216 217 218
        if (savedRetryAck == AckNone) {
            // Don't annoy the user with warnings about unexpected mission commands, just ignore them; ArduPilot updates home position using
            // spurious MISSION_ITEMs.
        } else {
            _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
219 220 221 222 223 224 225 226
        success = false;
    } else {
        success = true;
    }
    
    return success;
}

227
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
228
{
229
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
230 231 232 233 234 235 236 237
    
    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;
    
238 239 240 241 242
    mavlink_msg_mission_ack_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                        qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                        _dedicatedLink->mavlinkChannel(),
                                        &message,
                                        &missionAck);
Don Gagne's avatar
Don Gagne committed
243
    
244 245
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

246
    _finishTransaction(true);
Don Gagne's avatar
Don Gagne committed
247
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
248 249 250 251 252 253 254 255 256 257 258
}

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

    if (missionCount.count == 0) {
262
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
263
    } else {
264 265 266 267 268
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
269 270 271
    }
}

272
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
273
{
274 275 276 277
    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
278 279 280 281 282 283 284 285
        return;
    }
    
    mavlink_message_t           message;
    mavlink_mission_request_t   missionRequest;
    
    missionRequest.target_system =      _vehicle->id();
    missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
286
    missionRequest.seq =                _itemIndicesToRead[0];
Don Gagne's avatar
Don Gagne committed
287
    
288 289 290 291 292
    mavlink_msg_mission_request_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                            qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                            _dedicatedLink->mavlinkChannel(),
                                            &message,
                                            &missionRequest);
Don Gagne's avatar
Don Gagne committed
293
    
294
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
295
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
296 297 298 299 300 301 302 303 304 305 306 307 308 309
}

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;
    
310 311 312 313
    if (_itemIndicesToRead.contains(missionItem.seq)) {
        _requestItemRetryCount = 0;
        _itemIndicesToRead.removeOne(missionItem.seq);

314
        MissionItem* item = new MissionItem(missionItem.seq,
315 316 317 318 319 320 321 322 323 324 325 326
                                            (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
327

Don Gagne's avatar
Don Gagne committed
328
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
329 330 331 332
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

333 334 335 336 337 338 339
        _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;
340
        }
Don Gagne's avatar
Don Gagne committed
341
    }
342 343
    
    if (_itemIndicesToRead.count() == 0) {
344
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
345
    } else {
346
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
347 348 349 350 351
    }
}

void MissionManager::_clearMissionItems(void)
{
352
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
353 354 355 356 357 358 359 360 361 362 363 364 365 366 367
    _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;
    
368 369 370 371 372 373 374
    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;
375
        }
376 377
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
378 379 380 381 382
    }
    
    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;
    
383
    MissionItem* item = _missionItems[missionRequest.seq];
Don Gagne's avatar
Don Gagne committed
384 385 386 387 388 389 390 391 392
    
    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();
393 394 395
    missionItem.x =                 item->param5();
    missionItem.y =                 item->param6();
    missionItem.z =                 item->param7();
Don Gagne's avatar
Don Gagne committed
396 397 398 399
    missionItem.frame =             item->frame();
    missionItem.current =           missionRequest.seq == 0;
    missionItem.autocontinue =      item->autoContinue();
    
400 401 402 403 404
    mavlink_msg_mission_item_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                         qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                         _dedicatedLink->mavlinkChannel(),
                                         &messageOut,
                                         &missionItem);
Don Gagne's avatar
Don Gagne committed
405
    
406
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
407
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
408 409 410 411 412 413
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
DonLakeFlyer's avatar
DonLakeFlyer committed
414
    // Save the retry ack before calling _stopAckTimeout since we'll need it to determine what
415 416 417 418 419 420 421
    // 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
422 423 424 425 426
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
427
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
428 429 430 431

    switch (savedRetryAck) {
        case AckNone:
            // State machine is idle. Vehicle is confused.
Don Gagne's avatar
Don Gagne committed
432
            _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
433 434 435
            break;
        case AckMissionCount:
            // MISSION_COUNT message expected
436 437
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
438 439 440
            break;
        case AckMissionItem:
            // MISSION_ITEM expected
441 442
            _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);
443 444 445 446
            break;
        case AckMissionRequest:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
447
                if (_itemIndicesToWrite.count() == 0) {
448
                    qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
449
                    _finishTransaction(true);
450
                } else {
451 452
                    _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);
453 454
                }
            } else {
455 456
                _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
                _finishTransaction(false);
457 458
            }
            break;
Don Gagne's avatar
Don Gagne committed
459 460 461 462 463 464 465 466 467 468
        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
469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496
    }
}

/// 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:
497
            _handleMissionCurrent(message);
Don Gagne's avatar
Don Gagne committed
498 499 500 501
            break;
    }
}

502 503
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
504
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
505

506
    emit error(errorCode, errorMsg);
507
}
Don Gagne's avatar
Don Gagne committed
508 509 510 511

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
Don Gagne's avatar
Don Gagne committed
512
        case AckNone:
Don Gagne's avatar
Don Gagne committed
513
            return QString("No Ack");
Don Gagne's avatar
Don Gagne committed
514
        case AckMissionCount:
Don Gagne's avatar
Don Gagne committed
515
            return QString("MISSION_COUNT");
Don Gagne's avatar
Don Gagne committed
516
        case AckMissionItem:
Don Gagne's avatar
Don Gagne committed
517
            return QString("MISSION_ITEM");
Don Gagne's avatar
Don Gagne committed
518
        case AckMissionRequest:
Don Gagne's avatar
Don Gagne committed
519
            return QString("MISSION_REQUEST");
Don Gagne's avatar
Don Gagne committed
520 521
        case AckGuidedItem:
            return QString("Guided Mode Item");
Don Gagne's avatar
Don Gagne committed
522 523
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
524
            return QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
525
    }    
Don Gagne's avatar
Don Gagne committed
526
}
Don Gagne's avatar
Don Gagne committed
527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579

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");
    }
580
}
581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601

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;
}
602 603 604 605 606 607 608 609

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

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