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

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

Don Gagne's avatar
Don Gagne committed
45 46
}

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

51
    emit progressPct(0);
52 53 54 55 56 57 58 59

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

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

60
    _transactionInProgress = TransactionWrite;
61 62 63 64
    _retryCount = 0;
    emit inProgressChanged(true);
    _writeMissionCount();

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


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

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

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

85
    _clearAndDeleteMissionItems();
86 87

    int firstIndex = skipFirstItem ? 1 : 0;
88

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

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

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

104
    _writeMissionItemsWorker();
105 106 107 108 109
}

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

112 113
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
114

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

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

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

Don Gagne's avatar
Don Gagne committed
131 132 133 134 135 136 137
void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly)
{
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeArduPilotGuidedMissionItem called while transaction in progress";
        return;
    }

138
    _transactionInProgress = TransactionWrite;
Don Gagne's avatar
Don Gagne committed
139 140 141 142

    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;

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

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

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

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

    _retryCount = 0;
185
    _transactionInProgress = TransactionRead;
186 187 188 189 190 191 192 193 194
    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
195 196
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
197

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

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

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

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

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

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

    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;
273 274 275 276 277 278 279 280 281 282 283
    case AckMissionClearAll:
        // MISSION_ACK expected
        if (_retryCount > _maxRetryCount) {
            _sendError(VehicleError, QStringLiteral("Mission remove all, maximum retries exceeded."));
            _finishTransaction(false);
        } else {
            _retryCount++;
            qCDebug(MissionManagerLog) << "Retrying MISSION_CLEAR_ALL retry Count" << _retryCount;
            _removeAllWorker();
        }
        break;
284 285 286 287 288 289 290
    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
291 292
}

293
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
294
{
295
    _expectedAck = ack;
Don Gagne's avatar
Don Gagne committed
296 297 298
    _ackTimeoutTimer->start();
}

299 300 301
/// 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
302
{
303 304 305 306 307 308 309
    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
310 311
            // spurious MISSION_ITEMs.
        } else {
312 313 314
            // 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));
315
        }
316
        return false;
Don Gagne's avatar
Don Gagne committed
317 318 319
    }
}

320
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
321
{
322
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
323 324 325
    
    mavlink_message_t       message;
    mavlink_mission_ack_t   missionAck;
Don Gagne's avatar
Don Gagne committed
326 327

    memset(&missionAck, 0, sizeof(missionAck));
Don Gagne's avatar
Don Gagne committed
328 329 330 331 332
    
    missionAck.target_system =      _vehicle->id();
    missionAck.target_component =   MAV_COMP_ID_MISSIONPLANNER;
    missionAck.type =               MAV_MISSION_ACCEPTED;
    
333 334 335 336 337
    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
338
    
339 340
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

341
    _finishTransaction(true);
342
    emit newMissionItemsAvailable(false);
Don Gagne's avatar
Don Gagne committed
343 344 345 346 347 348
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
349
    if (!_checkForExpectedAck(AckMissionCount)) {
Don Gagne's avatar
Don Gagne committed
350 351
        return;
    }
352 353

    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
354 355
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
356 357 358
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << missionCount.count;

    if (missionCount.count == 0) {
359
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
360
    } else {
361 362 363 364 365
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
366 367 368
    }
}

369
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
370
{
371 372
    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
373 374
        return;
    }
375 376 377

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

378 379 380 381
    mavlink_message_t message;
    if (_vehicle->supportsMissionItemInt()) {
        mavlink_mission_request_int_t missionRequest;

Don Gagne's avatar
Don Gagne committed
382
        memset(&missionRequest, 0, sizeof(missionRequest));
383 384 385 386 387 388 389 390 391 392 393 394
        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
395
        memset(&missionRequest, 0, sizeof(missionRequest));
396 397 398 399 400 401 402 403 404 405
        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
406
    
407
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
408
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
409 410
}

411
void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
412 413
{
    
414
    if (!_checkForExpectedAck(AckMissionItem)) {
Don Gagne's avatar
Don Gagne committed
415 416
        return;
    }
417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435

    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,
436 437
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
438 439 440 441 442
        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);
443
        param7 =        (double)missionItem.z;
444 445 446 447 448 449 450 451
        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,
452 453
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
454 455 456 457 458 459 460 461 462 463
        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;
    }
464 465 466 467 468 469 470

    // 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
471
    
472
    qCDebug(MissionManagerLog) << "_handleMissionItem seq:command:current" << seq << command << isCurrentItem;
Don Gagne's avatar
Don Gagne committed
473
    
474 475 476 477 478 479 480 481 482 483 484 485 486 487 488
    if (_itemIndicesToRead.contains(seq)) {
        _itemIndicesToRead.removeOne(seq);

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

Don Gagne's avatar
Don Gagne committed
491
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
492 493 494 495
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

496 497
        _missionItems.append(item);
    } else {
498
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << seq;
499 500 501
        // We have to put the ack timeout back since it was removed above
        _startAckTimeout(AckMissionItem);
        return;
Don Gagne's avatar
Don Gagne committed
502
    }
503 504

    emit progressPct((double)seq / (double)_missionItems.count());
505
    
506
    _retryCount = 0;
507
    if (_itemIndicesToRead.count() == 0) {
508
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
509
    } else {
510
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
511 512 513 514 515
    }
}

void MissionManager::_clearMissionItems(void)
{
516
    _itemIndicesToRead.clear();
517
    _clearAndDeleteMissionItems();
Don Gagne's avatar
Don Gagne committed
518 519
}

520
void MissionManager::_handleMissionRequest(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
521 522 523
{
    mavlink_mission_request_t missionRequest;
    
524
    if (!_checkForExpectedAck(AckMissionRequest)) {
Don Gagne's avatar
Don Gagne committed
525 526 527 528
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
529 530 531 532 533 534 535
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber" << missionRequest.seq;

    if (missionRequest.seq > _missionItems.count() - 1) {
        _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;
    }
Don Gagne's avatar
Don Gagne committed
536

537 538
    emit progressPct((double)missionRequest.seq / (double)_missionItems.count());

Don Gagne's avatar
Don Gagne committed
539
    _lastMissionRequest = missionRequest.seq;
540
    if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
541
        qCDebug(MissionManagerLog) << "_handleMissionRequest sequence number requested which has already been sent, sending again:" << missionRequest.seq;
542 543
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
544 545
    }
    
546
    MissionItem* item = _missionItems[missionRequest.seq];
547
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:command" << missionRequest.seq << item->command();
548 549

    mavlink_message_t   messageOut;
550 551 552
    if (missionItemInt) {
        mavlink_mission_item_int_t missionItem;

Don Gagne's avatar
Don Gagne committed
553
        memset(&missionItem, 0, sizeof(missionItem));
554 555 556 557 558 559 560 561 562 563
        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);
564
        missionItem.z =                 item->param7();
565 566 567 568 569 570 571 572 573 574 575 576
        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
577
        memset(&missionItem, 0, sizeof(missionItem));
578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598
        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
599
    
600
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
601
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
602 603 604 605 606 607
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
608
    // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
609
    // type of a protocol sequence we are in.
610
    AckType_t savedExpectedAck = _expectedAck;
611 612
    
    // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
613
    // a protocol sequence error. Call _checkForExpectedAck with _retryAck so it will succeed no
614
    // matter what.
615
    if (!_checkForExpectedAck(_expectedAck)) {
Don Gagne's avatar
Don Gagne committed
616 617 618 619 620
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
621
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
622

623
    switch (savedExpectedAck) {
624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642
    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
643 644
                _finishTransaction(true);
            } else {
645
                _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
646 647
                _finishTransaction(false);
            }
648 649 650 651 652
        } 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;
653 654 655 656 657 658 659
    case AckMissionClearAll:
        // MISSION_ACK expected
        if (missionAck.type != MAV_MISSION_ACCEPTED) {
            _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle remove all failed.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
        }
        _finishTransaction(missionAck.type == MAV_MISSION_ACCEPTED);
        break;
660 661 662 663 664 665
    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
666
            _sendError(VehicleError, QString("Vehicle returned error: %1. %2Vehicle did not accept guided item.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
667 668 669
            _finishTransaction(false);
        }
        break;
Don Gagne's avatar
Don Gagne committed
670 671 672
    }
}

673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696
void MissionManager::_handleCameraFeedback(const mavlink_message_t& message)
{
    mavlink_camera_feedback_t feedback;

    mavlink_msg_camera_feedback_decode(&message, &feedback);

    QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
    qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
    emit cameraFeedback(imageCoordinate, feedback.img_idx);
}

void MissionManager::_handleCameraImageCaptured(const mavlink_message_t& message)
{
    mavlink_camera_image_captured_t feedback;

    mavlink_msg_camera_image_captured_decode(&message, &feedback);

    QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
    qCDebug(MissionManagerLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
    if (feedback.capture_result == 1) {
        emit cameraFeedback(imageCoordinate, feedback.image_index);
    }
}

Don Gagne's avatar
Don Gagne committed
697 698 699 700
/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
701 702 703
    case MAVLINK_MSG_ID_MISSION_COUNT:
        _handleMissionCount(message);
        break;
Don Gagne's avatar
Don Gagne committed
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
    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;
732 733 734 735 736 737 738 739

    case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
        _handleCameraFeedback(message);
        break;

    case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
        _handleCameraImageCaptured(message);
        break;
Don Gagne's avatar
Don Gagne committed
740 741 742
    }
}

743 744
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
745
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
746

747
    emit error(errorCode, errorMsg);
748
}
Don Gagne's avatar
Don Gagne committed
749 750 751 752

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
753 754 755 756 757 758 759 760 761 762 763 764 765 766
    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
767
}
Don Gagne's avatar
Don Gagne committed
768

Don Gagne's avatar
Don Gagne committed
769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802
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
803 804
QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
Don Gagne's avatar
Don Gagne committed
805 806 807
    QString resultString;
    QString lastRequestString = _lastMissionReqestString(result);

Don Gagne's avatar
Don Gagne committed
808
    switch (result) {
809
    case MAV_MISSION_ACCEPTED:
Don Gagne's avatar
Don Gagne committed
810
        resultString = QString("Mission accepted (MAV_MISSION_ACCEPTED)");
811 812
        break;
    case MAV_MISSION_ERROR:
Don Gagne's avatar
Don Gagne committed
813
        resultString = QString("Unspecified error (MAV_MISSION_ERROR)");
814 815
        break;
    case MAV_MISSION_UNSUPPORTED_FRAME:
Don Gagne's avatar
Don Gagne committed
816
        resultString = QString("Coordinate frame is not supported (MAV_MISSION_UNSUPPORTED_FRAME)");
817 818
        break;
    case MAV_MISSION_UNSUPPORTED:
Don Gagne's avatar
Don Gagne committed
819
        resultString = QString("Command is not supported (MAV_MISSION_UNSUPPORTED)");
820 821
        break;
    case MAV_MISSION_NO_SPACE:
Don Gagne's avatar
Don Gagne committed
822
        resultString = QString("Mission item exceeds storage space (MAV_MISSION_NO_SPACE)");
823 824
        break;
    case MAV_MISSION_INVALID:
Don Gagne's avatar
Don Gagne committed
825
        resultString = QString("One of the parameters has an invalid value (MAV_MISSION_INVALID)");
826 827
        break;
    case MAV_MISSION_INVALID_PARAM1:
Don Gagne's avatar
Don Gagne committed
828
        resultString = QString("Param1 has an invalid value (MAV_MISSION_INVALID_PARAM1)");
829 830
        break;
    case MAV_MISSION_INVALID_PARAM2:
Don Gagne's avatar
Don Gagne committed
831
        resultString = QString("Param2 has an invalid value (MAV_MISSION_INVALID_PARAM2)");
832 833
        break;
    case MAV_MISSION_INVALID_PARAM3:
Don Gagne's avatar
Don Gagne committed
834
        resultString = QString("Param3 has an invalid value (MAV_MISSION_INVALID_PARAM3)");
835 836
        break;
    case MAV_MISSION_INVALID_PARAM4:
Don Gagne's avatar
Don Gagne committed
837
        resultString = QString("Param4 has an invalid value (MAV_MISSION_INVALID_PARAM4)");
838 839
        break;
    case MAV_MISSION_INVALID_PARAM5_X:
Don Gagne's avatar
Don Gagne committed
840
        resultString = QString("X/Param5 has an invalid value (MAV_MISSION_INVALID_PARAM5_X)");
841 842
        break;
    case MAV_MISSION_INVALID_PARAM6_Y:
Don Gagne's avatar
Don Gagne committed
843
        resultString = QString("Y/Param6 has an invalid value (MAV_MISSION_INVALID_PARAM6_Y)");
844 845
        break;
    case MAV_MISSION_INVALID_PARAM7:
Don Gagne's avatar
Don Gagne committed
846
        resultString = QString("Param7 has an invalid value (MAV_MISSION_INVALID_PARAM7)");
847 848
        break;
    case MAV_MISSION_INVALID_SEQUENCE:
Don Gagne's avatar
Don Gagne committed
849
        resultString = QString("Received mission item out of sequence (MAV_MISSION_INVALID_SEQUENCE)");
850 851
        break;
    case MAV_MISSION_DENIED:
Don Gagne's avatar
Don Gagne committed
852
        resultString = QString("Not accepting any mission commands (MAV_MISSION_DENIED)");
853 854 855
        break;
    default:
        qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
856
        resultString = QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
857
    }
Don Gagne's avatar
Don Gagne committed
858 859

    return resultString + lastRequestString;
860
}
861 862 863

void MissionManager::_finishTransaction(bool success)
{
864 865
    emit progressPct(1);

866
    if (!success && _transactionInProgress == TransactionRead) {
867
        // Read from vehicle failed, clear partial list
868
        _clearAndDeleteMissionItems();
869
        emit newMissionItemsAvailable(false);
870 871
    }

872 873 874 875
    if (_transactionInProgress == TransactionWrite) {
        emit newMissionItemsAvailable(_missionItems.count() == 0);
    }

876 877 878
    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

879 880
    if (_transactionInProgress != TransactionNone) {
        _transactionInProgress = TransactionNone;
881 882
        emit inProgressChanged(false);
    }
883 884 885 886 887

    if (_resumeMission) {
        _resumeMission = false;
        emit resumeMissionReady();
    }
888 889 890 891
}

bool MissionManager::inProgress(void)
{
892
    return _transactionInProgress != TransactionNone;
893
}
894 895 896 897 898 899 900

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

901 902 903 904
    if (missionCurrent.seq != _currentMissionIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent currentIndex:" << missionCurrent.seq;
        _currentMissionIndex = missionCurrent.seq;
        emit currentIndexChanged(_currentMissionIndex);
905
    }
906

907 908 909 910
    if (_vehicle->flightMode() == _vehicle->missionFlightMode() && _currentMissionIndex != _lastCurrentIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent lastCurrentIndex:" << _currentMissionIndex;
        _lastCurrentIndex = _currentMissionIndex;
        emit lastCurrentIndexChanged(_lastCurrentIndex);
911
    }
912
}
913

914 915 916 917 918 919
void MissionManager::_removeAllWorker(void)
{
    mavlink_message_t message;

    qCDebug(MissionManagerLog) << "_removeAllWorker";

920 921
    emit progressPct(0);

922 923 924 925 926 927 928 929 930 931 932 933
    _dedicatedLink = _vehicle->priorityLink();
    mavlink_msg_mission_clear_all_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                            qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                            _dedicatedLink->mavlinkChannel(),
                                            &message,
                                            _vehicle->id(),
                                            MAV_COMP_ID_MISSIONPLANNER,
                                            MAV_MISSION_TYPE_MISSION);
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
    _startAckTimeout(AckMissionClearAll);
}

934 935
void MissionManager::removeAll(void)
{
936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952
    if (inProgress()) {
        return;
    }

    qCDebug(MissionManagerLog) << "removeAll";

    _clearAndDeleteMissionItems();

    _currentMissionIndex = -1;
    _lastCurrentIndex = -1;
    emit currentIndexChanged(-1);
    emit lastCurrentIndexChanged(-1);
    emit newMissionItemsAvailable(true /* removeAllRequested */);

    _transactionInProgress = TransactionClearAll;
    _retryCount = 0;
    emit inProgressChanged(true);
953

954
    _removeAllWorker();
955
}
956 957 958 959 960 961 962 963 964 965 966 967

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

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

968 969 970 971 972 973 974 975
    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;
        }
    }

976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997
    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;

998
    int resumeCommandCount = 0;
999 1000 1001
    for (int i=0; i<_missionItems.count(); i++) {
        MissionItem* oldItem = _missionItems[i];
        if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) {
1002 1003 1004
            if (i < resumeIndex) {
                resumeCommandCount++;
            }
1005 1006 1007 1008 1009 1010 1011
            MissionItem* newItem = new MissionItem(*oldItem, this);
            newItem->setIsCurrentItem( i == setCurrentIndex);
            newItem->setSequenceNumber(seqNum++);
            resumeMission.append(newItem);
        }
    }

1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096
    // 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--;
    }
1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118

    // 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();
}