MissionManager.cc 38.3 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
    , _resumeMission(false)
Don Gagne's avatar
Don Gagne committed
30
    , _lastMissionRequest(-1)
31 32
    , _currentMissionIndex(-1)
    , _lastCurrentIndex(-1)
Don Gagne's avatar
Don Gagne committed
33 34 35 36 37 38 39 40 41 42
{
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
    
    _ackTimeoutTimer = new QTimer(this);
    _ackTimeoutTimer->setSingleShot(true);
    _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
    
    connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
}

43
MissionManager::~MissionManager()
Don Gagne's avatar
Don Gagne committed
44
{
45

Don Gagne's avatar
Don Gagne committed
46 47
}

48 49
void MissionManager::_writeMissionItemsWorker(void)
{
Don Gagne's avatar
Don Gagne committed
50 51
    _lastMissionRequest = -1;

52 53 54 55 56 57 58 59 60 61 62 63 64 65
    emit newMissionItemsAvailable(_missionItems.count() == 0);

    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();

    // Prime write list
    for (int i=0; i<_missionItems.count(); i++) {
        _itemIndicesToWrite << i;
    }

    _writeTransactionInProgress = true;
    _retryCount = 0;
    emit inProgressChanged(true);
    _writeMissionCount();

66 67 68 69
    _currentMissionIndex = -1;
    _lastCurrentIndex = -1;
    emit currentIndexChanged(-1);
    emit lastCurrentIndexChanged(-1);
70 71 72
}


73
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
Don Gagne's avatar
Don Gagne committed
74
{
75 76 77 78
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

79 80 81 82 83
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
        return;
    }

84 85
    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();

86
    _clearAndDeleteMissionItems();
87 88

    int firstIndex = skipFirstItem ? 1 : 0;
89

90
    for (int i=firstIndex; i<missionItems.count(); i++) {
91 92
        MissionItem* item = new MissionItem(*missionItems[i]);
        _missionItems.append(item);
93

94
        item->setIsCurrentItem(i == firstIndex);
95

96
        if (skipFirstItem) {
97
            // Home is in sequence 0, remainder of items start at sequence 1
98
            item->setSequenceNumber(item->sequenceNumber() - 1);
Don Gagne's avatar
Don Gagne committed
99
            if (item->command() == MAV_CMD_DO_JUMP) {
100 101
                item->setParam1((int)item->param1() - 1);
            }
Don Gagne's avatar
Don Gagne committed
102 103
        }
    }
104

105
    _writeMissionItemsWorker();
106 107 108 109 110
}

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

113 114
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
115

Don Gagne's avatar
Don Gagne committed
116
    memset(&missionCount, 0, sizeof(missionCount));
117 118 119
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
120

121
    _dedicatedLink = _vehicle->priorityLink();
122 123 124 125 126 127
    mavlink_msg_mission_count_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                          qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                          _dedicatedLink->mavlinkChannel(),
                                          &message,
                                          &missionCount);

128
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
129 130 131
    _startAckTimeout(AckMissionRequest);
}

Don Gagne's avatar
Don Gagne committed
132 133 134 135 136 137 138 139 140 141 142 143
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;

Don Gagne's avatar
Don Gagne committed
144
    memset(&missionItem, 8, sizeof(missionItem));
Don Gagne's avatar
Don Gagne committed
145
    missionItem.target_system =     _vehicle->id();
146
    missionItem.target_component =  _vehicle->defaultComponentId();
Don Gagne's avatar
Don Gagne committed
147 148 149 150 151 152 153 154 155 156 157 158 159 160
    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();
161 162 163 164 165 166
    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
167 168 169 170 171
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
    _startAckTimeout(AckGuidedItem);
    emit inProgressChanged(true);
}

172
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
173
{
174 175 176 177
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
178
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
179 180 181 182 183

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

    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
186
    _readTransactionInProgress = true;
187 188 189 190 191 192 193 194 195
    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
196 197
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
198

Don Gagne's avatar
Don Gagne committed
199 200
    memset(&request, 0, sizeof(request));

201
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
202
    _clearMissionItems();
203

Don Gagne's avatar
Don Gagne committed
204 205
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
206

207
    _dedicatedLink = _vehicle->priorityLink();
208 209 210 211 212
    mavlink_msg_mission_request_list_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                 qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                 _dedicatedLink->mavlinkChannel(),
                                                 &message,
                                                 &request);
213

214
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
215 216 217
    _startAckTimeout(AckMissionCount);
}

Don Gagne's avatar
Don Gagne committed
218 219
void MissionManager::_ackTimeout(void)
{
220
    if (_expectedAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
221 222
        return;
    }
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 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280

    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
281 282
}

283
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
284
{
285
    _expectedAck = ack;
Don Gagne's avatar
Don Gagne committed
286 287 288
    _ackTimeoutTimer->start();
}

289 290 291
/// 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
292
{
293 294 295 296 297 298 299
    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
300 301
            // spurious MISSION_ITEMs.
        } else {
302 303 304
            // 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));
305
        }
306
        return false;
Don Gagne's avatar
Don Gagne committed
307 308 309
    }
}

310
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
311
{
312
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
313 314 315
    
    mavlink_message_t       message;
    mavlink_mission_ack_t   missionAck;
Don Gagne's avatar
Don Gagne committed
316 317

    memset(&missionAck, 0, sizeof(missionAck));
Don Gagne's avatar
Don Gagne committed
318 319 320 321 322
    
    missionAck.target_system =      _vehicle->id();
    missionAck.target_component =   MAV_COMP_ID_MISSIONPLANNER;
    missionAck.type =               MAV_MISSION_ACCEPTED;
    
323 324 325 326 327
    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
328
    
329 330
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

331
    _finishTransaction(true);
332
    emit newMissionItemsAvailable(false);
Don Gagne's avatar
Don Gagne committed
333 334 335 336 337 338
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
339
    if (!_checkForExpectedAck(AckMissionCount)) {
Don Gagne's avatar
Don Gagne committed
340 341
        return;
    }
342 343

    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
344 345
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
346 347 348
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << missionCount.count;

    if (missionCount.count == 0) {
349
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
350
    } else {
351 352 353 354 355
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
356 357 358
    }
}

359
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
360
{
361 362
    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
363 364
        return;
    }
365 366 367

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

368 369 370 371
    mavlink_message_t message;
    if (_vehicle->supportsMissionItemInt()) {
        mavlink_mission_request_int_t missionRequest;

Don Gagne's avatar
Don Gagne committed
372
        memset(&missionRequest, 0, sizeof(missionRequest));
373 374 375 376 377 378 379 380 381 382 383 384
        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;

Don Gagne's avatar
Don Gagne committed
385
        memset(&missionRequest, 0, sizeof(missionRequest));
386 387 388 389 390 391 392 393 394 395
        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
396
    
397
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
398
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
399 400
}

401
void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
402 403
{
    
404
    if (!_checkForExpectedAck(AckMissionItem)) {
Don Gagne's avatar
Don Gagne committed
405 406
        return;
    }
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425

    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,
426 427
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
428 429 430 431 432
        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);
433
        param7 =        (double)missionItem.z;
434 435 436 437 438 439 440 441
        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,
442 443
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
444 445 446 447 448 449 450 451 452 453
        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;
    }
454 455 456 457 458 459 460

    // We don't support editing ALT_INT frames so change on the way in.
    if (frame == MAV_FRAME_GLOBAL_INT) {
        frame = MAV_FRAME_GLOBAL;
    } else if (frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
        frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
    }
Don Gagne's avatar
Don Gagne committed
461
    
462
    qCDebug(MissionManagerLog) << "_handleMissionItem seq:command:current" << seq << command << isCurrentItem;
Don Gagne's avatar
Don Gagne committed
463
    
464 465 466 467 468 469 470 471 472 473 474 475 476 477 478
    if (_itemIndicesToRead.contains(seq)) {
        _itemIndicesToRead.removeOne(seq);

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

Don Gagne's avatar
Don Gagne committed
481
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
482 483 484 485
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

486 487
        _missionItems.append(item);
    } else {
488
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << seq;
489 490 491
        // We have to put the ack timeout back since it was removed above
        _startAckTimeout(AckMissionItem);
        return;
Don Gagne's avatar
Don Gagne committed
492
    }
493
    
494
    _retryCount = 0;
495
    if (_itemIndicesToRead.count() == 0) {
496
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
497
    } else {
498
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
499 500 501 502 503
    }
}

void MissionManager::_clearMissionItems(void)
{
504
    _itemIndicesToRead.clear();
505
    _clearAndDeleteMissionItems();
Don Gagne's avatar
Don Gagne committed
506 507
}

508
void MissionManager::_handleMissionRequest(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
509 510 511
{
    mavlink_mission_request_t missionRequest;
    
512
    if (!_checkForExpectedAck(AckMissionRequest)) {
Don Gagne's avatar
Don Gagne committed
513 514 515 516
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
Don Gagne's avatar
Don Gagne committed
517 518

    _lastMissionRequest = missionRequest.seq;
519 520 521 522 523 524 525
    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;
526
        }
527 528
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
529 530
    }
    
531
    MissionItem* item = _missionItems[missionRequest.seq];
532
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:command" << missionRequest.seq << item->command();
533 534

    mavlink_message_t   messageOut;
535 536 537
    if (missionItemInt) {
        mavlink_mission_item_int_t missionItem;

Don Gagne's avatar
Don Gagne committed
538
        memset(&missionItem, 0, sizeof(missionItem));
539 540 541 542 543 544 545 546 547 548
        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);
549
        missionItem.z =                 item->param7();
550 551 552 553 554 555 556 557 558 559 560 561
        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;

Don Gagne's avatar
Don Gagne committed
562
        memset(&missionItem, 0, sizeof(missionItem));
563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583
        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
584
    
585
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
586
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
587 588 589 590 591 592
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
593
    // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
594
    // type of a protocol sequence we are in.
595
    AckType_t savedExpectedAck = _expectedAck;
596 597
    
    // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
598
    // a protocol sequence error. Call _checkForExpectedAck with _retryAck so it will succeed no
599
    // matter what.
600
    if (!_checkForExpectedAck(_expectedAck)) {
Don Gagne's avatar
Don Gagne committed
601 602 603 604 605
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
606
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
607

608
    switch (savedExpectedAck) {
609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627
    case AckNone:
        // State machine is idle. Vehicle is confused.
        _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
        break;
    case AckMissionCount:
        // MISSION_COUNT message expected
        _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
        _finishTransaction(false);
        break;
    case AckMissionItem:
        // MISSION_ITEM expected
        _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
        _finishTransaction(false);
        break;
    case AckMissionRequest:
        // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
        if (missionAck.type == MAV_MISSION_ACCEPTED) {
            if (_itemIndicesToWrite.count() == 0) {
                qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
Don Gagne's avatar
Don Gagne committed
628 629
                _finishTransaction(true);
            } else {
630
                _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()));
Don Gagne's avatar
Don Gagne committed
631 632
                _finishTransaction(false);
            }
633 634 635 636 637 638 639 640 641 642 643
        } else {
            _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
        }
        break;
    case AckGuidedItem:
        // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
        if (missionAck.type == MAV_MISSION_ACCEPTED) {
            qCDebug(MissionManagerLog) << "_handleMissionAck guided mode item accepted";
            _finishTransaction(true);
        } else {
Don Gagne's avatar
Don Gagne committed
644
            _sendError(VehicleError, QString("Vehicle returned error: %1. %2Vehicle did not accept guided item.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
645 646 647
            _finishTransaction(false);
        }
        break;
Don Gagne's avatar
Don Gagne committed
648 649 650 651 652 653 654
    }
}

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

659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685
    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
686 687 688
    }
}

689 690
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
691
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
692

693
    emit error(errorCode, errorMsg);
694
}
Don Gagne's avatar
Don Gagne committed
695 696 697 698

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
699 700 701 702 703 704 705 706 707 708 709 710 711 712
    case AckNone:
        return QString("No Ack");
    case AckMissionCount:
        return QString("MISSION_COUNT");
    case AckMissionItem:
        return QString("MISSION_ITEM");
    case AckMissionRequest:
        return QString("MISSION_REQUEST");
    case AckGuidedItem:
        return QString("Guided Mode Item");
    default:
        qWarning(MissionManagerLog) << "Fell off end of switch statement";
        return QString("QGC Internal Error");
    }
Don Gagne's avatar
Don Gagne committed
713
}
Don Gagne's avatar
Don Gagne committed
714

Don Gagne's avatar
Don Gagne committed
715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748
QString MissionManager::_lastMissionReqestString(MAV_MISSION_RESULT result)
{
    if (_lastMissionRequest != -1 && _lastMissionRequest >= 0 && _lastMissionRequest < _missionItems.count()) {
        MissionItem* item = _missionItems[_lastMissionRequest];

        switch (result) {
        case MAV_MISSION_UNSUPPORTED_FRAME:
            return QString(". Frame: %1").arg(item->frame());
        case MAV_MISSION_UNSUPPORTED:
            return QString(". Command: %1").arg(item->command());
        case MAV_MISSION_INVALID_PARAM1:
            return QString(". Param1: %1").arg(item->param1());
        case MAV_MISSION_INVALID_PARAM2:
            return QString(". Param2: %1").arg(item->param2());
        case MAV_MISSION_INVALID_PARAM3:
            return QString(". Param3: %1").arg(item->param3());
        case MAV_MISSION_INVALID_PARAM4:
            return QString(". Param4: %1").arg(item->param4());
        case MAV_MISSION_INVALID_PARAM5_X:
            return QString(". Param5: %1").arg(item->param5());
        case MAV_MISSION_INVALID_PARAM6_Y:
            return QString(". Param6: %1").arg(item->param6());
        case MAV_MISSION_INVALID_PARAM7:
            return QString(". Param7: %1").arg(item->param7());
        case MAV_MISSION_INVALID_SEQUENCE:
            return QString(". Sequence: %1").arg(item->sequenceNumber());
        default:
            break;
        }
    }

    return QString();
}

Don Gagne's avatar
Don Gagne committed
749 750
QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
Don Gagne's avatar
Don Gagne committed
751 752 753
    QString resultString;
    QString lastRequestString = _lastMissionReqestString(result);

Don Gagne's avatar
Don Gagne committed
754
    switch (result) {
755
    case MAV_MISSION_ACCEPTED:
Don Gagne's avatar
Don Gagne committed
756
        resultString = QString("Mission accepted (MAV_MISSION_ACCEPTED)");
757 758
        break;
    case MAV_MISSION_ERROR:
Don Gagne's avatar
Don Gagne committed
759
        resultString = QString("Unspecified error (MAV_MISSION_ERROR)");
760 761
        break;
    case MAV_MISSION_UNSUPPORTED_FRAME:
Don Gagne's avatar
Don Gagne committed
762
        resultString = QString("Coordinate frame is not supported (MAV_MISSION_UNSUPPORTED_FRAME)");
763 764
        break;
    case MAV_MISSION_UNSUPPORTED:
Don Gagne's avatar
Don Gagne committed
765
        resultString = QString("Command is not supported (MAV_MISSION_UNSUPPORTED)");
766 767
        break;
    case MAV_MISSION_NO_SPACE:
Don Gagne's avatar
Don Gagne committed
768
        resultString = QString("Mission item exceeds storage space (MAV_MISSION_NO_SPACE)");
769 770
        break;
    case MAV_MISSION_INVALID:
Don Gagne's avatar
Don Gagne committed
771
        resultString = QString("One of the parameters has an invalid value (MAV_MISSION_INVALID)");
772 773
        break;
    case MAV_MISSION_INVALID_PARAM1:
Don Gagne's avatar
Don Gagne committed
774
        resultString = QString("Param1 has an invalid value (MAV_MISSION_INVALID_PARAM1)");
775 776
        break;
    case MAV_MISSION_INVALID_PARAM2:
Don Gagne's avatar
Don Gagne committed
777
        resultString = QString("Param2 has an invalid value (MAV_MISSION_INVALID_PARAM2)");
778 779
        break;
    case MAV_MISSION_INVALID_PARAM3:
Don Gagne's avatar
Don Gagne committed
780
        resultString = QString("Param3 has an invalid value (MAV_MISSION_INVALID_PARAM3)");
781 782
        break;
    case MAV_MISSION_INVALID_PARAM4:
Don Gagne's avatar
Don Gagne committed
783
        resultString = QString("Param4 has an invalid value (MAV_MISSION_INVALID_PARAM4)");
784 785
        break;
    case MAV_MISSION_INVALID_PARAM5_X:
Don Gagne's avatar
Don Gagne committed
786
        resultString = QString("X/Param5 has an invalid value (MAV_MISSION_INVALID_PARAM5_X)");
787 788
        break;
    case MAV_MISSION_INVALID_PARAM6_Y:
Don Gagne's avatar
Don Gagne committed
789
        resultString = QString("Y/Param6 has an invalid value (MAV_MISSION_INVALID_PARAM6_Y)");
790 791
        break;
    case MAV_MISSION_INVALID_PARAM7:
Don Gagne's avatar
Don Gagne committed
792
        resultString = QString("Param7 has an invalid value (MAV_MISSION_INVALID_PARAM7)");
793 794
        break;
    case MAV_MISSION_INVALID_SEQUENCE:
Don Gagne's avatar
Don Gagne committed
795
        resultString = QString("Received mission item out of sequence (MAV_MISSION_INVALID_SEQUENCE)");
796 797
        break;
    case MAV_MISSION_DENIED:
Don Gagne's avatar
Don Gagne committed
798
        resultString = QString("Not accepting any mission commands (MAV_MISSION_DENIED)");
799 800 801
        break;
    default:
        qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
802
        resultString = QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
803
    }
Don Gagne's avatar
Don Gagne committed
804 805

    return resultString + lastRequestString;
806
}
807 808 809 810 811

void MissionManager::_finishTransaction(bool success)
{
    if (!success && _readTransactionInProgress) {
        // Read from vehicle failed, clear partial list
812
        _clearAndDeleteMissionItems();
813
        emit newMissionItemsAvailable(false);
814 815 816 817 818
    }

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

819 820 821 822 823
    if (_readTransactionInProgress || _writeTransactionInProgress) {
        _readTransactionInProgress = false;
        _writeTransactionInProgress = false;
        emit inProgressChanged(false);
    }
824 825 826 827 828

    if (_resumeMission) {
        _resumeMission = false;
        emit resumeMissionReady();
    }
829 830 831 832 833 834
}

bool MissionManager::inProgress(void)
{
    return _readTransactionInProgress || _writeTransactionInProgress;
}
835 836 837 838 839 840 841

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

842 843 844 845
    if (missionCurrent.seq != _currentMissionIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent currentIndex:" << missionCurrent.seq;
        _currentMissionIndex = missionCurrent.seq;
        emit currentIndexChanged(_currentMissionIndex);
846
    }
847

848 849 850 851
    if (_vehicle->flightMode() == _vehicle->missionFlightMode() && _currentMissionIndex != _lastCurrentIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent lastCurrentIndex:" << _currentMissionIndex;
        _lastCurrentIndex = _currentMissionIndex;
        emit lastCurrentIndexChanged(_lastCurrentIndex);
852
    }
853
}
854 855 856 857 858 859 860

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

    writeMissionItems(emptyList);
}
861 862 863 864 865 866 867 868 869 870 871 872

void MissionManager::generateResumeMission(int resumeIndex)
{
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

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

873 874 875 876 877 878 879 880
    for (int i=0; i<_missionItems.count(); i++) {
        MissionItem* item = _missionItems[i];
        if (item->command() == MAV_CMD_DO_JUMP) {
            qgcApp()->showMessage(tr("Unable to generate resume mission due to MAV_CMD_DO_JUMP command."));
            return;
        }
    }

881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902
    int seqNum = 0;
    QList<MissionItem*> resumeMission;

    QList<MAV_CMD> includedResumeCommands;

    // If any command in this list occurs before the resumeIndex it will be added to the front of the mission
    includedResumeCommands << MAV_CMD_DO_CONTROL_VIDEO
                           << MAV_CMD_DO_SET_ROI
                           << MAV_CMD_DO_DIGICAM_CONFIGURE
                           << MAV_CMD_DO_DIGICAM_CONTROL
                           << MAV_CMD_DO_MOUNT_CONFIGURE
                           << MAV_CMD_DO_MOUNT_CONTROL
                           << MAV_CMD_DO_SET_CAM_TRIGG_DIST
                           << MAV_CMD_DO_FENCE_ENABLE
                           << MAV_CMD_IMAGE_START_CAPTURE
                           << MAV_CMD_IMAGE_STOP_CAPTURE
                           << MAV_CMD_VIDEO_START_CAPTURE
                           << MAV_CMD_VIDEO_STOP_CAPTURE;

    bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle();
    int setCurrentIndex = addHomePosition ? 1 : 0;

903
    int resumeCommandCount = 0;
904 905 906
    for (int i=0; i<_missionItems.count(); i++) {
        MissionItem* oldItem = _missionItems[i];
        if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) {
907 908 909
            if (i < resumeIndex) {
                resumeCommandCount++;
            }
910 911 912 913 914 915 916
            MissionItem* newItem = new MissionItem(*oldItem, this);
            newItem->setIsCurrentItem( i == setCurrentIndex);
            newItem->setSequenceNumber(seqNum++);
            resumeMission.append(newItem);
        }
    }

917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001
    // De-dup and remove no-ops from the commands which were added to the front of the mission
    bool foundROI = false;
    bool foundCamTrigDist = false;
    QList<int> imageStartCameraIds;
    QList<int> imageStopCameraIds;
    QList<int> videoStartCameraIds;
    QList<int> videoStopCameraIds;
    while (resumeIndex >= 0) {
        MissionItem* resumeItem = resumeMission[resumeIndex];
        switch (resumeItem->command()) {
        case MAV_CMD_DO_SET_ROI:
            // Only keep the last one
            if (foundROI) {
                resumeMission.removeAt(resumeIndex);
            }
            foundROI = true;
            break;
        case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
            // Only keep the last one
            if (foundCamTrigDist) {
                resumeMission.removeAt(resumeIndex);
            }
            foundCamTrigDist = true;
            break;
        case MAV_CMD_IMAGE_START_CAPTURE:
        {
            // FIXME: Handle single image capture
            int cameraId = resumeItem->param6();

            if (resumeItem->param1() == 0) {
                // This is an individual image capture command, remove it
                resumeMission.removeAt(resumeIndex);
                break;
            }
            // If we already found an image stop, then all image start/stop commands are useless
            // De-dup repeated image start commands
            // Otherwise keep only the last image start
            if (imageStopCameraIds.contains(cameraId) || imageStartCameraIds.contains(cameraId)) {
                resumeMission.removeAt(resumeIndex);
            }
            if (!imageStopCameraIds.contains(cameraId)) {
                imageStopCameraIds.append(cameraId);
            }
        }
            break;
        case MAV_CMD_IMAGE_STOP_CAPTURE:
        {
            int cameraId = resumeItem->param1();
            // Image stop only matters to kill all previous image starts
            if (!imageStopCameraIds.contains(cameraId)) {
                imageStopCameraIds.append(cameraId);
            }
            resumeMission.removeAt(resumeIndex);
        }
            break;
        case MAV_CMD_VIDEO_START_CAPTURE:
        {
            int cameraId = resumeItem->param1();
            // If we already found an video stop, then all video start/stop commands are useless
            // De-dup repeated video start commands
            // Otherwise keep only the last video start
            if (videoStopCameraIds.contains(cameraId) || videoStopCameraIds.contains(cameraId)) {
                resumeMission.removeAt(resumeIndex);
            }
            if (!videoStopCameraIds.contains(cameraId)) {
                videoStopCameraIds.append(cameraId);
            }
        }
            break;
        case MAV_CMD_VIDEO_STOP_CAPTURE:
        {
            int cameraId = resumeItem->param1();
            // Video stop only matters to kill all previous video starts
            if (!videoStopCameraIds.contains(cameraId)) {
                videoStopCameraIds.append(cameraId);
            }
            resumeMission.removeAt(resumeIndex);
        }
            break;
        default:
            break;
        }

        resumeIndex--;
    }
1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023

    // Send to vehicle
    _clearAndDeleteMissionItems();
    for (int i=0; i<resumeMission.count(); i++) {
        _missionItems.append(new MissionItem(*resumeMission[i], this));
    }
    _resumeMission = true;
    _writeMissionItemsWorker();

    // Clean up no longer needed resume items
    for (int i=0; i<resumeMission.count(); i++) {
        resumeMission[i]->deleteLater();
    }
}

void MissionManager::_clearAndDeleteMissionItems(void)
{
    for (int i=0; i<_missionItems.count(); i++) {
        _missionItems[i]->deleteLater();
    }
    _missionItems.clear();
}