MissionManager.cc 29.7 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
    , _ackTimeoutTimer(NULL)
26
    , _expectedAck(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(missionItems.count() == 0);
Don Gagne's avatar
Don Gagne committed
77

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

85
    _writeTransactionInProgress = true;
86 87 88 89 90 91 92 93
    _retryCount = 0;
    emit inProgressChanged(true);
    _writeMissionCount();
}

/// This begins the write sequence with the vehicle. This may be called during a retry.
void MissionManager::_writeMissionCount(void)
{
94
    qCDebug(MissionManagerLog) << "_writeMissionCount count:_retryCount" << _missionItems.count() << _retryCount;
95

96 97
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
98

99 100 101
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
102

103
    _dedicatedLink = _vehicle->priorityLink();
104 105 106 107 108 109
    mavlink_msg_mission_count_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                          qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                          _dedicatedLink->mavlinkChannel(),
                                          &message,
                                          &missionCount);

110
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
111 112 113
    _startAckTimeout(AckMissionRequest);
}

Don Gagne's avatar
Don Gagne committed
114 115 116 117 118 119 120 121 122 123 124 125 126
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();
127
    missionItem.target_component =  _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
128 129 130 131 132 133 134 135 136 137 138 139 140 141
    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();
142 143 144 145 146 147
    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
148 149 150 151 152
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
    _startAckTimeout(AckGuidedItem);
    emit inProgressChanged(true);
}

153
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
154
{
155 156 157 158
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
159
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
160 161 162 163 164

    if (inProgress()) {
        qCDebug(MissionManagerLog) << "requestMissionItems called while transaction in progress";
        return;
    }
165 166

    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
167
    _readTransactionInProgress = true;
168 169 170 171 172 173 174 175 176
    emit inProgressChanged(true);
    _requestList();
}

/// Internal call to request list of mission items. May be called during a retry sequence.
void MissionManager::_requestList(void)
{
    qCDebug(MissionManagerLog) << "_requestList retry count" << _retryCount;

Don Gagne's avatar
Don Gagne committed
177 178
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
179

180
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
181
    _clearMissionItems();
182

Don Gagne's avatar
Don Gagne committed
183 184
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
185

186
    _dedicatedLink = _vehicle->priorityLink();
187 188 189 190 191
    mavlink_msg_mission_request_list_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                 qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                 _dedicatedLink->mavlinkChannel(),
                                                 &message,
                                                 &request);
192

193
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
194 195 196
    _startAckTimeout(AckMissionCount);
}

Don Gagne's avatar
Don Gagne committed
197 198
void MissionManager::_ackTimeout(void)
{
199
    if (_expectedAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
200 201
        return;
    }
202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259

    switch (_expectedAck) {
    case AckNone:
        qCWarning(MissionManagerLog) << "_ackTimeout timeout with AckNone";
        _sendError(InternalError, "Internal error occurred during Mission Item communication: _ackTimeOut:_expectedAck == AckNone");
        break;
    case AckMissionCount:
        // MISSION_COUNT message expected
        if (_retryCount > _maxRetryCount) {
            _sendError(VehicleError, QStringLiteral("Mission request list failed, maximum retries exceeded."));
            _finishTransaction(false);
        } else {
            _retryCount++;
            qCDebug(MissionManagerLog) << "Retrying REQUEST_LIST retry Count" << _retryCount;
            _requestList();
        }
        break;
    case AckMissionItem:
        // MISSION_ITEM expected
        if (_retryCount > _maxRetryCount) {
            _sendError(VehicleError, QStringLiteral("Mission read failed, maximum retries exceeded."));
            _finishTransaction(false);
        } else {
            _retryCount++;
            qCDebug(MissionManagerLog) << "Retrying MISSION_REQUEST retry Count" << _retryCount;
            _requestNextMissionItem();
        }
        break;
    case AckMissionRequest:
        // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
        if (_itemIndicesToWrite.count() == 0) {
            // Vehicle did not send final MISSION_ACK at end of sequence
            _sendError(VehicleError, QStringLiteral("Mission write failed, vehicle failed to send final ack."));
            _finishTransaction(false);
        } else if (_itemIndicesToWrite[0] == 0) {
            // Vehicle did not respond to MISSION_COUNT, try again
            if (_retryCount > _maxRetryCount) {
                _sendError(VehicleError, QStringLiteral("Mission write mission count failed, maximum retries exceeded."));
                _finishTransaction(false);
            } else {
                _retryCount++;
                qCDebug(MissionManagerLog) << "Retrying MISSION_COUNT retry Count" << _retryCount;
                _writeMissionCount();
            }
        } else {
            // Vehicle did not request all items from ground station
            _sendError(AckTimeoutError, QString("Vehicle did not request all items from ground station: %1").arg(_ackTypeToString(_expectedAck)));
            _expectedAck = AckNone;
            _finishTransaction(false);
        }
        break;
    case AckGuidedItem:
        // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
    default:
        _sendError(AckTimeoutError, QString("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(_expectedAck)));
        _expectedAck = AckNone;
        _finishTransaction(false);
    }
Don Gagne's avatar
Don Gagne committed
260 261
}

262
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
263
{
264
    _expectedAck = ack;
Don Gagne's avatar
Don Gagne committed
265 266 267
    _ackTimeoutTimer->start();
}

268 269 270
/// Checks the received ack against the expected ack. If they match the ack timeout timer will be stopped.
/// @return true: received ack matches expected ack
bool MissionManager::_checkForExpectedAck(AckType_t receivedAck)
Don Gagne's avatar
Don Gagne committed
271
{
272 273 274 275 276 277 278
    if (receivedAck == _expectedAck) {
        _expectedAck = AckNone;
        _ackTimeoutTimer->stop();
        return true;
    } else {
        if (_expectedAck == AckNone) {
            // Don't worry about unexpected mission commands, just ignore them; ArduPilot updates home position using
279 280
            // spurious MISSION_ITEMs.
        } else {
281 282 283
            // We just warn in this case, this could be crap left over from a previous transaction or the vehicle going bonkers.
            // Whatever it is we let the ack timeout handle any error output to the user.
            qCDebug(MissionManagerLog) << QString("Out of sequence ack expected:received %1:%2").arg(_ackTypeToString(_expectedAck)).arg(_ackTypeToString(receivedAck));
284
        }
285
        return false;
Don Gagne's avatar
Don Gagne committed
286 287 288
    }
}

289
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
290
{
291
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
292 293 294 295 296 297 298 299
    
    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;
    
300 301 302 303 304
    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
305
    
306 307
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

308
    _finishTransaction(true);
309
    emit newMissionItemsAvailable(false);
Don Gagne's avatar
Don Gagne committed
310 311 312 313 314 315
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
316
    if (!_checkForExpectedAck(AckMissionCount)) {
Don Gagne's avatar
Don Gagne committed
317 318
        return;
    }
319 320

    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
321 322
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
323 324 325
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << missionCount.count;

    if (missionCount.count == 0) {
326
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
327
    } else {
328 329 330 331 332
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
333 334 335
    }
}

336
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
337
{
338 339
    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
340 341
        return;
    }
342 343 344

    qCDebug(MissionManagerLog) << "_requestNextMissionItem sequenceNumber:retry" << _itemIndicesToRead[0] << _retryCount;

345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370
    mavlink_message_t message;
    if (_vehicle->supportsMissionItemInt()) {
        mavlink_mission_request_int_t missionRequest;

        missionRequest.target_system =      _vehicle->id();
        missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
        missionRequest.seq =                _itemIndicesToRead[0];

        mavlink_msg_mission_request_int_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                    qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                    _dedicatedLink->mavlinkChannel(),
                                                    &message,
                                                    &missionRequest);
    } else {
        mavlink_mission_request_t missionRequest;

        missionRequest.target_system =      _vehicle->id();
        missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
        missionRequest.seq =                _itemIndicesToRead[0];

        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
371
    
372
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
373
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
374 375
}

376
void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
377 378
{
    
379
    if (!_checkForExpectedAck(AckMissionItem)) {
Don Gagne's avatar
Don Gagne committed
380 381
        return;
    }
382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428

    MAV_CMD     command;
    MAV_FRAME   frame;
    double      param1;
    double      param2;
    double      param3;
    double      param4;
    double      param5;
    double      param6;
    double      param7;
    bool        autoContinue;
    bool        isCurrentItem;
    int         seq;

    if (missionItemInt) {
        mavlink_mission_item_int_t missionItem;
        mavlink_msg_mission_item_int_decode(&message, &missionItem);

        command =       (MAV_CMD)missionItem.command,
        frame =         (MAV_FRAME)missionItem.frame,
        param1 =        missionItem.param1;
        param2 =        missionItem.param2;
        param3 =        missionItem.param3;
        param4 =        missionItem.param4;
        param5 =        (double)missionItem.x / qPow(10.0, 7.0);
        param6 =        (double)missionItem.y / qPow(10.0, 7.0);
        param7 =        (double)missionItem.z / qPow(10.0, 7.0);
        autoContinue =  missionItem.autocontinue;
        isCurrentItem = missionItem.current;
        seq =           missionItem.seq;
    } else {
        mavlink_mission_item_t missionItem;
        mavlink_msg_mission_item_decode(&message, &missionItem);

        command =       (MAV_CMD)missionItem.command,
        frame =         (MAV_FRAME)missionItem.frame,
        param1 =        missionItem.param1;
        param2 =        missionItem.param2;
        param3 =        missionItem.param3;
        param4 =        missionItem.param4;
        param5 =        missionItem.x;
        param6 =        missionItem.y;
        param7 =        missionItem.z;
        autoContinue =  missionItem.autocontinue;
        isCurrentItem = missionItem.current;
        seq =           missionItem.seq;
    }
Don Gagne's avatar
Don Gagne committed
429
    
430
    qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << seq << command;
Don Gagne's avatar
Don Gagne committed
431
    
432 433 434 435 436 437 438 439 440 441 442 443 444 445 446
    if (_itemIndicesToRead.contains(seq)) {
        _itemIndicesToRead.removeOne(seq);

        MissionItem* item = new MissionItem(seq,
                                            command,
                                            frame,
                                            param1,
                                            param2,
                                            param3,
                                            param4,
                                            param5,
                                            param6,
                                            param7,
                                            autoContinue,
                                            isCurrentItem,
447
                                            this);
Don Gagne's avatar
Don Gagne committed
448

Don Gagne's avatar
Don Gagne committed
449
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
450 451 452 453
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

454 455
        _missionItems.append(item);
    } else {
456
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << seq;
457 458 459
        // We have to put the ack timeout back since it was removed above
        _startAckTimeout(AckMissionItem);
        return;
Don Gagne's avatar
Don Gagne committed
460
    }
461
    
462
    _retryCount = 0;
463
    if (_itemIndicesToRead.count() == 0) {
464
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
465
    } else {
466
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
467 468 469 470 471
    }
}

void MissionManager::_clearMissionItems(void)
{
472
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
473 474 475
    _missionItems.clear();
}

476
void MissionManager::_handleMissionRequest(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
477 478 479
{
    mavlink_mission_request_t missionRequest;
    
480
    if (!_checkForExpectedAck(AckMissionRequest)) {
Don Gagne's avatar
Don Gagne committed
481 482 483 484 485
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
    
486 487 488 489 490 491 492
    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;
493
        }
494 495
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
496 497
    }
    
498 499 500 501
    MissionItem* item = _missionItems[missionRequest.seq];
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq << item->command();

    mavlink_message_t   messageOut;
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 538 539 540 541 542 543 544 545 546 547 548 549
    if (missionItemInt) {
        mavlink_mission_item_int_t missionItem;


        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();
        missionItem.x =                 item->param5() * qPow(10.0, 7.0);
        missionItem.y =                 item->param6() * qPow(10.0, 7.0);
        missionItem.z =                 item->param7() * qPow(10.0, 7.0);
        missionItem.frame =             item->frame();
        missionItem.current =           missionRequest.seq == 0;
        missionItem.autocontinue =      item->autoContinue();

        mavlink_msg_mission_item_int_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                 qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                 _dedicatedLink->mavlinkChannel(),
                                                 &messageOut,
                                                 &missionItem);
    } else {
        mavlink_mission_item_t missionItem;

        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();
        missionItem.x =                 item->param5();
        missionItem.y =                 item->param6();
        missionItem.z =                 item->param7();
        missionItem.frame =             item->frame();
        missionItem.current =           missionRequest.seq == 0;
        missionItem.autocontinue =      item->autoContinue();

        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
550
    
551
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
552
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
553 554 555 556 557 558
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
559
    // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
560
    // type of a protocol sequence we are in.
561
    AckType_t savedExpectedAck = _expectedAck;
562 563
    
    // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
564
    // a protocol sequence error. Call _checkForExpectedAck with _retryAck so it will succeed no
565
    // matter what.
566
    if (!_checkForExpectedAck(_expectedAck)) {
Don Gagne's avatar
Don Gagne committed
567 568 569 570 571
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
572
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
573

574
    switch (savedExpectedAck) {
575 576
        case AckNone:
            // State machine is idle. Vehicle is confused.
Don Gagne's avatar
Don Gagne committed
577
            _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
578 579 580
            break;
        case AckMissionCount:
            // MISSION_COUNT message expected
581 582
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
583 584 585
            break;
        case AckMissionItem:
            // MISSION_ITEM expected
586
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
587
            _finishTransaction(false);
588 589 590 591
            break;
        case AckMissionRequest:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
592
                if (_itemIndicesToWrite.count() == 0) {
593
                    qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
594
                    _finishTransaction(true);
595
                } else {
596 597
                    _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);
598 599
                }
            } else {
600 601
                _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
                _finishTransaction(false);
602 603
            }
            break;
Don Gagne's avatar
Don Gagne committed
604 605 606
        case AckGuidedItem:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
607
                qCDebug(MissionManagerLog) << "_handleMissionAck guided mode item accepted";
Don Gagne's avatar
Don Gagne committed
608 609 610 611 612 613
                _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
614 615 616 617 618 619 620
    }
}

/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
621 622 623
    case MAVLINK_MSG_ID_MISSION_COUNT:
        _handleMissionCount(message);
        break;
Don Gagne's avatar
Don Gagne committed
624

625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651
    case MAVLINK_MSG_ID_MISSION_ITEM:
        _handleMissionItem(message, false /* missionItemInt */);
        break;

    case MAVLINK_MSG_ID_MISSION_ITEM_INT:
        _handleMissionItem(message, true /* missionItemInt */);
        break;

    case MAVLINK_MSG_ID_MISSION_REQUEST:
        _handleMissionRequest(message, false /* missionItemInt */);
        break;

    case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
        _handleMissionRequest(message, true /* missionItemInt */);
        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:
        _handleMissionCurrent(message);
        break;
Don Gagne's avatar
Don Gagne committed
652 653 654
    }
}

655 656
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
657
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
658

659
    emit error(errorCode, errorMsg);
660
}
Don Gagne's avatar
Don Gagne committed
661 662 663 664

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
Don Gagne's avatar
Don Gagne committed
665
        case AckNone:
Don Gagne's avatar
Don Gagne committed
666
            return QString("No Ack");
Don Gagne's avatar
Don Gagne committed
667
        case AckMissionCount:
Don Gagne's avatar
Don Gagne committed
668
            return QString("MISSION_COUNT");
Don Gagne's avatar
Don Gagne committed
669
        case AckMissionItem:
Don Gagne's avatar
Don Gagne committed
670
            return QString("MISSION_ITEM");
Don Gagne's avatar
Don Gagne committed
671
        case AckMissionRequest:
Don Gagne's avatar
Don Gagne committed
672
            return QString("MISSION_REQUEST");
Don Gagne's avatar
Don Gagne committed
673 674
        case AckGuidedItem:
            return QString("Guided Mode Item");
Don Gagne's avatar
Don Gagne committed
675 676
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
677
            return QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
678
    }    
Don Gagne's avatar
Don Gagne committed
679
}
Don Gagne's avatar
Don Gagne committed
680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732

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");
    }
733
}
734 735 736 737 738 739

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

    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

746 747 748 749 750
    if (_readTransactionInProgress || _writeTransactionInProgress) {
        _readTransactionInProgress = false;
        _writeTransactionInProgress = false;
        emit inProgressChanged(false);
    }
751 752 753 754 755 756
}

bool MissionManager::inProgress(void)
{
    return _readTransactionInProgress || _writeTransactionInProgress;
}
757 758 759 760 761 762 763 764

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

    if (missionCurrent.seq != _currentMissionItem) {
765
        qCDebug(MissionManagerLog) << "_handleMissionCurrent seq:" << missionCurrent.seq;
766 767 768 769
        _currentMissionItem = missionCurrent.seq;
        emit currentItemChanged(_currentMissionItem);
    }
}
770 771 772 773 774 775 776

void MissionManager::removeAll(void)
{
    QList<MissionItem*> emptyList;

    writeMissionItems(emptyList);
}