MissionManager.cc 43.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"
19 20
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
Don Gagne's avatar
Don Gagne committed
21 22 23 24

QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")

MissionManager::MissionManager(Vehicle* vehicle)
25
    : _vehicle(vehicle)
26
    , _dedicatedLink(NULL)
Don Gagne's avatar
Don Gagne committed
27
    , _ackTimeoutTimer(NULL)
28
    , _expectedAck(AckNone)
29
    , _transactionInProgress(TransactionNone)
30
    , _resumeMission(false)
Don Gagne's avatar
Don Gagne committed
31
    , _lastMissionRequest(-1)
32 33
    , _currentMissionIndex(-1)
    , _lastCurrentIndex(-1)
34
    , _cachedLastCurrentIndex(-1)
Don Gagne's avatar
Don Gagne committed
35 36 37 38 39 40 41 42 43 44
{
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
    
    _ackTimeoutTimer = new QTimer(this);
    _ackTimeoutTimer->setSingleShot(true);
    _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
    
    connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
}

45
MissionManager::~MissionManager()
Don Gagne's avatar
Don Gagne committed
46
{
47

Don Gagne's avatar
Don Gagne committed
48 49
}

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

54
    emit progressPct(0);
55

56
    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _writeMissionItems.count();
57 58

    // Prime write list
59
    _itemIndicesToWrite.clear();
60
    for (int i=0; i<_writeMissionItems.count(); i++) {
61 62 63
        _itemIndicesToWrite << i;
    }

64
    _transactionInProgress = TransactionWrite;
65 66 67 68 69 70
    _retryCount = 0;
    emit inProgressChanged(true);
    _writeMissionCount();
}


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

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

82
    _clearAndDeleteWriteMissionItems();
83

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

    int firstIndex = skipFirstItem ? 1 : 0;
87

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

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

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

103
    _writeMissionItemsWorker();
104 105 106 107 108
}

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

111 112
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
113

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

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

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

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

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

    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;

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

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

DonLakeFlyer's avatar
DonLakeFlyer committed
176
    qCDebug(MissionManagerLog) << "loadFromVehicle read sequence";
177 178

    if (inProgress()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
179
        qCDebug(MissionManagerLog) << "loadFromVehicle called while transaction in progress";
180 181
        return;
    }
182 183

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

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
216 217
void MissionManager::_ackTimeout(void)
{
218
    if (_expectedAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
219 220
        return;
    }
221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271

    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;
272 273 274 275 276 277 278 279 280 281 282
    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;
283 284 285 286 287 288 289
    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
290 291
}

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

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

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

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

340
    _finishTransaction(true);
Don Gagne's avatar
Don Gagne committed
341 342 343 344 345 346
}

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

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

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

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

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

376 377 378 379
    mavlink_message_t message;
    if (_vehicle->supportsMissionItemInt()) {
        mavlink_mission_request_int_t missionRequest;

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

409
void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
410
{
411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428
    MAV_CMD     command;
    MAV_FRAME   frame;
    double      param1;
    double      param2;
    double      param3;
    double      param4;
    double      param5;
    double      param6;
    double      param7;
    bool        autoContinue;
    bool        isCurrentItem;
    int         seq;

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

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

    // 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
464
    
465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482

    bool ardupilotHomePositionUpdate = false;
    if (!_checkForExpectedAck(AckMissionItem)) {
        if (_vehicle->apmFirmware() && seq ==  0) {
            ardupilotHomePositionUpdate = true;
        } else {
            qCDebug(MissionManagerLog) << "_handleMissionItem dropping spurious item seq:command:current" << seq << command << isCurrentItem;
            return;
        }
    }

    qCDebug(MissionManagerLog) << "_handleMissionItem seq:command:current:ardupilotHomePositionUpdate" << seq << command << isCurrentItem << ardupilotHomePositionUpdate;

    if (ardupilotHomePositionUpdate) {
        QGeoCoordinate newHomePosition(param5, param6, param7);
        _vehicle->_setHomePosition(newHomePosition);
        return;
    }
Don Gagne's avatar
Don Gagne committed
483
    
484 485 486 487 488 489 490 491 492 493 494 495 496 497 498
    if (_itemIndicesToRead.contains(seq)) {
        _itemIndicesToRead.removeOne(seq);

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

Don Gagne's avatar
Don Gagne committed
501
        if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
Don Gagne's avatar
Don Gagne committed
502 503 504 505
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

506 507
        _missionItems.append(item);
    } else {
508
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << seq;
509 510 511
        // We have to put the ack timeout back since it was removed above
        _startAckTimeout(AckMissionItem);
        return;
Don Gagne's avatar
Don Gagne committed
512
    }
513 514

    emit progressPct((double)seq / (double)_missionItems.count());
515
    
516
    _retryCount = 0;
517
    if (_itemIndicesToRead.count() == 0) {
518
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
519
    } else {
520
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
521 522 523 524 525
    }
}

void MissionManager::_clearMissionItems(void)
{
526
    _itemIndicesToRead.clear();
527
    _clearAndDeleteMissionItems();
Don Gagne's avatar
Don Gagne committed
528 529
}

530
void MissionManager::_handleMissionRequest(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
531 532 533
{
    mavlink_mission_request_t missionRequest;
    
534
    if (!_checkForExpectedAck(AckMissionRequest)) {
Don Gagne's avatar
Don Gagne committed
535 536 537 538
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
539 540
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber" << missionRequest.seq;

541 542
    if (missionRequest.seq > _writeMissionItems.count() - 1) {
        _sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_writeMissionItems.count()).arg(missionRequest.seq));
543 544 545
        _finishTransaction(false);
        return;
    }
Don Gagne's avatar
Don Gagne committed
546

547
    emit progressPct((double)missionRequest.seq / (double)_writeMissionItems.count());
548

Don Gagne's avatar
Don Gagne committed
549
    _lastMissionRequest = missionRequest.seq;
550
    if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
551
        qCDebug(MissionManagerLog) << "_handleMissionRequest sequence number requested which has already been sent, sending again:" << missionRequest.seq;
552 553
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
554 555
    }
    
556
    MissionItem* item = _writeMissionItems[missionRequest.seq];
557
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:command" << missionRequest.seq << item->command();
558 559

    mavlink_message_t   messageOut;
560 561 562
    if (missionItemInt) {
        mavlink_mission_item_int_t missionItem;

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

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

633
    switch (savedExpectedAck) {
634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652
    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
653 654
                _finishTransaction(true);
            } else {
655
                _sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence, missed count %1.").arg(_itemIndicesToWrite.count()));
Don Gagne's avatar
Don Gagne committed
656 657
                _finishTransaction(false);
            }
658
        } else {
659
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
660 661 662
            _finishTransaction(false);
        }
        break;
663 664 665 666 667 668 669
    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;
670 671 672 673 674 675
    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
676
            _sendError(VehicleError, QString("Vehicle returned error: %1. %2Vehicle did not accept guided item.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
677 678 679
            _finishTransaction(false);
        }
        break;
Don Gagne's avatar
Don Gagne committed
680 681 682 683 684 685
    }
}
/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
686 687 688
    case MAVLINK_MSG_ID_MISSION_COUNT:
        _handleMissionCount(message);
        break;
Don Gagne's avatar
Don Gagne committed
689

690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716
    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;
717 718 719 720

    case MAVLINK_MSG_ID_HEARTBEAT:
        _handleHeartbeat(message);
        break;
Don Gagne's avatar
Don Gagne committed
721 722 723
    }
}

724 725
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
726
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
727

728
    emit error(errorCode, errorMsg);
729
}
Don Gagne's avatar
Don Gagne committed
730 731 732 733

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
734 735 736 737 738 739 740 741 742 743 744 745 746 747
    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
748
}
Don Gagne's avatar
Don Gagne committed
749

Don Gagne's avatar
Don Gagne committed
750 751
QString MissionManager::_lastMissionReqestString(MAV_MISSION_RESULT result)
{
752 753
    if (_lastMissionRequest != -1 && _lastMissionRequest >= 0 && _lastMissionRequest < _writeMissionItems.count()) {
        MissionItem* item = _writeMissionItems[_lastMissionRequest];
Don Gagne's avatar
Don Gagne committed
754 755 756 757 758

        switch (result) {
        case MAV_MISSION_UNSUPPORTED_FRAME:
            return QString(". Frame: %1").arg(item->frame());
        case MAV_MISSION_UNSUPPORTED:
759 760 761 762 763 764 765 766 767 768
        {
            const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, item->command());
            QString friendlyName;
            QString rawName;
            if (uiInfo) {
                friendlyName = uiInfo->friendlyName();
                rawName = uiInfo->rawName();
            }
            return QString(". Command: (%1, %2, %3)").arg(friendlyName).arg(rawName).arg(item->command());
        }
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
        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
793 794
QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
Don Gagne's avatar
Don Gagne committed
795 796 797
    QString resultString;
    QString lastRequestString = _lastMissionReqestString(result);

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

    return resultString + lastRequestString;
850
}
851 852 853

void MissionManager::_finishTransaction(bool success)
{
854 855
    emit progressPct(1);

856 857 858
    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

DonLakeFlyer's avatar
DonLakeFlyer committed
859 860 861
    // First thing we do is clear the transaction. This way inProgesss is off when we signal transaction complete.
    TransactionType_t currentTransactionType = _transactionInProgress;
    _transactionInProgress = TransactionNone;
862
    if (currentTransactionType != TransactionNone) {
863
        _transactionInProgress = TransactionNone;
864
        qDebug() << "inProgressChanged";
865 866
        emit inProgressChanged(false);
    }
867

DonLakeFlyer's avatar
DonLakeFlyer committed
868 869 870 871 872 873 874 875 876
    switch (currentTransactionType) {
    case TransactionRead:
        if (!success) {
            // Read from vehicle failed, clear partial list
            _clearAndDeleteMissionItems();
        }
        emit newMissionItemsAvailable(false);
        break;
    case TransactionWrite:
877
        if (success) {
878 879 880
            // Write succeeded, update internal list to be current            
            _currentMissionIndex = -1;
            _lastCurrentIndex = -1;
881
            _cachedLastCurrentIndex = -1;
882 883
            emit currentIndexChanged(-1);
            emit lastCurrentIndexChanged(-1);
884 885 886 887 888 889 890 891 892 893
            _clearAndDeleteMissionItems();
            for (int i=0; i<_writeMissionItems.count(); i++) {
                _missionItems.append(_writeMissionItems[i]);
            }
            _writeMissionItems.clear();
        } else {
            // Write failed, throw out the write list
            _clearAndDeleteWriteMissionItems();
        }
        emit sendComplete(!success /* error */);
DonLakeFlyer's avatar
DonLakeFlyer committed
894 895
        break;
    case TransactionRemoveAll:
896
        emit removeAllComplete(!success /* error */);
DonLakeFlyer's avatar
DonLakeFlyer committed
897 898 899 900 901
        break;
    default:
        break;
    }

902 903
    if (_resumeMission) {
        _resumeMission = false;
904 905 906 907 908
        if (success) {
            emit resumeMissionReady();
        } else {
            emit resumeMissionUploadFail();
        }
909
    }
910 911 912 913
}

bool MissionManager::inProgress(void)
{
914
    return _transactionInProgress != TransactionNone;
915
}
916 917 918 919 920 921 922

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

923 924 925 926
    if (missionCurrent.seq != _currentMissionIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent currentIndex:" << missionCurrent.seq;
        _currentMissionIndex = missionCurrent.seq;
        emit currentIndexChanged(_currentMissionIndex);
927
    }
928

929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948
    if (_currentMissionIndex != _lastCurrentIndex) {
        // We have to be careful of an RTL sequence causing a change of index to the DO_LAND_START sequence. This also triggers
        // a flight mode change away from mission flight mode. So we only update _lastCurrentIndex when the flight mode is mission.
        // But we can run into problems where we may get the MISSION_CURRENT message for the RTL/DO_LAND_START sequenc change prior
        // to the HEARTBEAT message which contains the flight mode change which will cause things to work incorrectly. To fix this
        // We force the sequencing of HEARTBEAT following by MISSION_CURRENT by caching the possible _lastCurrentIndex update until
        // the next HEARTBEAT comes through.
        qCDebug(MissionManagerLog) << "_handleMissionCurrent caching _lastCurrentIndex for possible update:" << _currentMissionIndex;
        _cachedLastCurrentIndex = _currentMissionIndex;
    }
}

void MissionManager::_handleHeartbeat(const mavlink_message_t& message)
{
    Q_UNUSED(message);

    if (_cachedLastCurrentIndex != -1 &&  _vehicle->flightMode() == _vehicle->missionFlightMode()) {
        qCDebug(MissionManagerLog) << "_handleHeartbeat updating lastCurrentIndex from cached value:" << _cachedLastCurrentIndex;
        _lastCurrentIndex = _cachedLastCurrentIndex;
        _cachedLastCurrentIndex = -1;
949
        emit lastCurrentIndexChanged(_lastCurrentIndex);
950
    }
951
}
952

953 954 955 956 957 958
void MissionManager::_removeAllWorker(void)
{
    mavlink_message_t message;

    qCDebug(MissionManagerLog) << "_removeAllWorker";

959 960
    emit progressPct(0);

961 962 963 964 965 966 967 968 969 970 971 972
    _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);
}

973 974
void MissionManager::removeAll(void)
{
975 976 977 978 979 980 981 982 983 984
    if (inProgress()) {
        return;
    }

    qCDebug(MissionManagerLog) << "removeAll";

    _clearAndDeleteMissionItems();

    _currentMissionIndex = -1;
    _lastCurrentIndex = -1;
985
    _cachedLastCurrentIndex = -1;
986 987 988
    emit currentIndexChanged(-1);
    emit lastCurrentIndexChanged(-1);

DonLakeFlyer's avatar
DonLakeFlyer committed
989
    _transactionInProgress = TransactionRemoveAll;
990 991
    _retryCount = 0;
    emit inProgressChanged(true);
992

993
    _removeAllWorker();
994
}
995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006

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

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

1007 1008 1009 1010 1011 1012 1013 1014
    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;
        }
    }

1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031
    // Be anal about crap input
    resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1));

    // Adjust resume index to be a location based command
    const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command());
    if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) {
        // We have to back up to the last command which the vehicle flies through
        while (--resumeIndex > 0) {
            uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command());
            if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) {
                // Found it
                break;
            }

        }
    }
    resumeIndex = qMax(0, resumeIndex);
1032

1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048
    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
1049
                           << MAV_CMD_VIDEO_STOP_CAPTURE
1050 1051 1052
                           << MAV_CMD_DO_CHANGE_SPEED
                           << MAV_CMD_SET_CAMERA_MODE
                           << MAV_CMD_NAV_TAKEOFF;
1053 1054 1055

    bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle();

1056
    int prefixCommandCount = 0;
1057 1058 1059
    for (int i=0; i<_missionItems.count(); i++) {
        MissionItem* oldItem = _missionItems[i];
        if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) {
1060
            if (i < resumeIndex) {
1061
                prefixCommandCount++;
1062
            }
1063
            MissionItem* newItem = new MissionItem(*oldItem, this);
1064
            newItem->setIsCurrentItem(false);
1065 1066 1067
            resumeMission.append(newItem);
        }
    }
1068
    prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count()));  // Anal prevention against crashes
1069

1070 1071
    // De-dup and remove no-ops from the commands which were added to the front of the mission
    bool foundROI = false;
1072 1073 1074 1075 1076
    bool foundCameraSetMode = false;
    bool foundCameraStartStop = false;
    prefixCommandCount--;   // Change from count to array index
    while (prefixCommandCount >= 0) {
        MissionItem* resumeItem = resumeMission[prefixCommandCount];
1077
        switch (resumeItem->command()) {
1078 1079 1080 1081 1082 1083 1084
        case MAV_CMD_SET_CAMERA_MODE:
            // Only keep the last one
            if (foundCameraSetMode) {
                resumeMission.removeAt(prefixCommandCount);
            }
            foundCameraSetMode = true;
            break;
1085 1086 1087
        case MAV_CMD_DO_SET_ROI:
            // Only keep the last one
            if (foundROI) {
1088
                resumeMission.removeAt(prefixCommandCount);
1089 1090 1091 1092 1093 1094
            }
            foundROI = true;
            break;
        case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
        case MAV_CMD_IMAGE_STOP_CAPTURE:
        case MAV_CMD_VIDEO_START_CAPTURE:
1095 1096 1097 1098
        case MAV_CMD_VIDEO_STOP_CAPTURE:
            // Only keep the first of these commands that are found
            if (foundCameraStartStop) {
                resumeMission.removeAt(prefixCommandCount);
1099
            }
1100
            foundCameraStartStop = true;
1101
            break;
1102
        case MAV_CMD_IMAGE_START_CAPTURE:
Don Gagne's avatar
Don Gagne committed
1103 1104
            if (resumeItem->param3() != 0) {
                // Remove commands which do not trigger by time
1105
                resumeMission.removeAt(prefixCommandCount);
Don Gagne's avatar
Don Gagne committed
1106
                break;
1107
            }
Don Gagne's avatar
Don Gagne committed
1108 1109
            if (foundCameraStartStop) {
                // Only keep the first of these commands that are found
1110 1111 1112
                resumeMission.removeAt(prefixCommandCount);
            }
            foundCameraStartStop = true;
1113 1114 1115 1116 1117
            break;
        default:
            break;
        }

1118
        prefixCommandCount--;
1119
    }
1120

1121 1122 1123 1124 1125 1126 1127 1128
    // Adjust sequence numbers and current item
    int seqNum = 0;
    for (int i=0; i<resumeMission.count(); i++) {
        resumeMission[i]->setSequenceNumber(seqNum++);
    }
    int setCurrentIndex = addHomePosition ? 1 : 0;
    resumeMission[setCurrentIndex]->setIsCurrentItem(true);

1129
    // Send to vehicle
1130
    _clearAndDeleteWriteMissionItems();
1131
    for (int i=0; i<resumeMission.count(); i++) {
1132
        _writeMissionItems.append(new MissionItem(*resumeMission[i], this));
1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149
    }
    _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();
}
1150 1151 1152 1153 1154 1155 1156 1157 1158


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