MissionManager.cc 42.5 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)
Don Gagne's avatar
Don Gagne committed
34 35 36 37 38 39 40 41 42 43
{
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
    
    _ackTimeoutTimer = new QTimer(this);
    _ackTimeoutTimer->setSingleShot(true);
    _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
    
    connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
}

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

Don Gagne's avatar
Don Gagne committed
47 48
}

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

53
    emit progressPct(0);
54

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

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

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


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

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

81
    _clearAndDeleteWriteMissionItems();
82

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

    int firstIndex = skipFirstItem ? 1 : 0;
86

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

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

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

102
    _writeMissionItemsWorker();
103 104 105 106 107
}

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

110 111
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
112

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

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

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

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

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

    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

408
void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt)
Don Gagne's avatar
Don Gagne committed
409
{
410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427
    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,
428 429
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
430 431 432 433 434
        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);
435
        param7 =        (double)missionItem.z;
436 437 438 439 440 441 442 443
        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,
444 445
                frame =         (MAV_FRAME)missionItem.frame,
                param1 =        missionItem.param1;
446 447 448 449 450 451 452 453 454 455
        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;
    }
456 457 458 459 460 461 462

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

    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
482
    
483 484 485 486 487 488 489 490 491 492 493 494 495 496 497
    if (_itemIndicesToRead.contains(seq)) {
        _itemIndicesToRead.removeOne(seq);

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

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

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

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

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

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

540 541
    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));
542 543 544
        _finishTransaction(false);
        return;
    }
Don Gagne's avatar
Don Gagne committed
545

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

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

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

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

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

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

689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715
    case MAVLINK_MSG_ID_MISSION_ITEM:
        _handleMissionItem(message, false /* missionItemInt */);
        break;

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

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

    case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
        _handleMissionRequest(message, true /* missionItemInt */);
        break;

    case MAVLINK_MSG_ID_MISSION_ACK:
        _handleMissionAck(message);
        break;

    case MAVLINK_MSG_ID_MISSION_ITEM_REACHED:
        // FIXME: NYI
        break;

    case MAVLINK_MSG_ID_MISSION_CURRENT:
        _handleMissionCurrent(message);
        break;
Don Gagne's avatar
Don Gagne committed
716 717 718
    }
}

719 720
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
721
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
722

723
    emit error(errorCode, errorMsg);
724
}
Don Gagne's avatar
Don Gagne committed
725 726 727 728

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
729 730 731 732 733 734 735 736 737 738 739 740 741 742
    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
743
}
Don Gagne's avatar
Don Gagne committed
744

Don Gagne's avatar
Don Gagne committed
745 746
QString MissionManager::_lastMissionReqestString(MAV_MISSION_RESULT result)
{
747 748
    if (_lastMissionRequest != -1 && _lastMissionRequest >= 0 && _lastMissionRequest < _writeMissionItems.count()) {
        MissionItem* item = _writeMissionItems[_lastMissionRequest];
Don Gagne's avatar
Don Gagne committed
749 750 751 752 753

        switch (result) {
        case MAV_MISSION_UNSUPPORTED_FRAME:
            return QString(". Frame: %1").arg(item->frame());
        case MAV_MISSION_UNSUPPORTED:
754 755 756 757 758 759 760 761 762 763
        {
            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
764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787
        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
788 789
QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
Don Gagne's avatar
Don Gagne committed
790 791 792
    QString resultString;
    QString lastRequestString = _lastMissionReqestString(result);

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

    return resultString + lastRequestString;
845
}
846 847 848

void MissionManager::_finishTransaction(bool success)
{
849 850
    emit progressPct(1);

851 852 853
    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

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

DonLakeFlyer's avatar
DonLakeFlyer committed
863 864 865 866 867 868 869 870 871
    switch (currentTransactionType) {
    case TransactionRead:
        if (!success) {
            // Read from vehicle failed, clear partial list
            _clearAndDeleteMissionItems();
        }
        emit newMissionItemsAvailable(false);
        break;
    case TransactionWrite:
872
        if (success) {
873 874 875 876 877
            // Write succeeded, update internal list to be current            
            _currentMissionIndex = -1;
            _lastCurrentIndex = -1;
            emit currentIndexChanged(-1);
            emit lastCurrentIndexChanged(-1);
878 879 880 881 882 883 884 885 886 887
            _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
888 889
        break;
    case TransactionRemoveAll:
890
        emit removeAllComplete(!success /* error */);
DonLakeFlyer's avatar
DonLakeFlyer committed
891 892 893 894 895
        break;
    default:
        break;
    }

896 897
    if (_resumeMission) {
        _resumeMission = false;
898 899 900 901 902
        if (success) {
            emit resumeMissionReady();
        } else {
            emit resumeMissionUploadFail();
        }
903
    }
904 905 906 907
}

bool MissionManager::inProgress(void)
{
908
    return _transactionInProgress != TransactionNone;
909
}
910 911 912 913 914 915 916

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

917 918 919 920
    if (missionCurrent.seq != _currentMissionIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent currentIndex:" << missionCurrent.seq;
        _currentMissionIndex = missionCurrent.seq;
        emit currentIndexChanged(_currentMissionIndex);
921
    }
922

923 924 925 926
    if (_vehicle->flightMode() == _vehicle->missionFlightMode() && _currentMissionIndex != _lastCurrentIndex) {
        qCDebug(MissionManagerLog) << "_handleMissionCurrent lastCurrentIndex:" << _currentMissionIndex;
        _lastCurrentIndex = _currentMissionIndex;
        emit lastCurrentIndexChanged(_lastCurrentIndex);
927
    }
928
}
929

930 931 932 933 934 935
void MissionManager::_removeAllWorker(void)
{
    mavlink_message_t message;

    qCDebug(MissionManagerLog) << "_removeAllWorker";

936 937
    emit progressPct(0);

938 939 940 941 942 943 944 945 946 947 948 949
    _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);
}

950 951
void MissionManager::removeAll(void)
{
952 953 954 955 956 957 958 959 960 961 962 963 964
    if (inProgress()) {
        return;
    }

    qCDebug(MissionManagerLog) << "removeAll";

    _clearAndDeleteMissionItems();

    _currentMissionIndex = -1;
    _lastCurrentIndex = -1;
    emit currentIndexChanged(-1);
    emit lastCurrentIndexChanged(-1);

DonLakeFlyer's avatar
DonLakeFlyer committed
965
    _transactionInProgress = TransactionRemoveAll;
966 967
    _retryCount = 0;
    emit inProgressChanged(true);
968

969
    _removeAllWorker();
970
}
971 972 973 974 975 976 977 978 979 980 981 982

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

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

983 984 985 986 987 988 989 990
    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;
        }
    }

991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007
    // 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);
1008

1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024
    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
1025
                           << MAV_CMD_VIDEO_STOP_CAPTURE
1026 1027 1028
                           << MAV_CMD_DO_CHANGE_SPEED
                           << MAV_CMD_SET_CAMERA_MODE
                           << MAV_CMD_NAV_TAKEOFF;
1029 1030 1031

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

1032
    int prefixCommandCount = 0;
1033 1034 1035
    for (int i=0; i<_missionItems.count(); i++) {
        MissionItem* oldItem = _missionItems[i];
        if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) {
1036
            if (i < resumeIndex) {
1037
                prefixCommandCount++;
1038
            }
1039
            MissionItem* newItem = new MissionItem(*oldItem, this);
1040
            newItem->setIsCurrentItem(false);
1041 1042 1043
            resumeMission.append(newItem);
        }
    }
1044
    prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count()));  // Anal prevention against crashes
1045

1046 1047
    // De-dup and remove no-ops from the commands which were added to the front of the mission
    bool foundROI = false;
1048 1049 1050 1051 1052
    bool foundCameraSetMode = false;
    bool foundCameraStartStop = false;
    prefixCommandCount--;   // Change from count to array index
    while (prefixCommandCount >= 0) {
        MissionItem* resumeItem = resumeMission[prefixCommandCount];
1053
        switch (resumeItem->command()) {
1054 1055 1056 1057 1058 1059 1060
        case MAV_CMD_SET_CAMERA_MODE:
            // Only keep the last one
            if (foundCameraSetMode) {
                resumeMission.removeAt(prefixCommandCount);
            }
            foundCameraSetMode = true;
            break;
1061 1062 1063
        case MAV_CMD_DO_SET_ROI:
            // Only keep the last one
            if (foundROI) {
1064
                resumeMission.removeAt(prefixCommandCount);
1065 1066 1067 1068 1069 1070
            }
            foundROI = true;
            break;
        case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
        case MAV_CMD_IMAGE_STOP_CAPTURE:
        case MAV_CMD_VIDEO_START_CAPTURE:
1071 1072 1073 1074
        case MAV_CMD_VIDEO_STOP_CAPTURE:
            // Only keep the first of these commands that are found
            if (foundCameraStartStop) {
                resumeMission.removeAt(prefixCommandCount);
1075
            }
1076
            foundCameraStartStop = true;
1077
            break;
1078 1079 1080 1081
        case MAV_CMD_IMAGE_START_CAPTURE:
            // Only keep the first of these commands that are found
            if (foundCameraStartStop) {
                resumeMission.removeAt(prefixCommandCount);
1082
            }
1083 1084 1085 1086 1087
            if (resumeItem->param3() != 0) {
                // Remove commands which do no trigger by time
                resumeMission.removeAt(prefixCommandCount);
            }
            foundCameraStartStop = true;
1088 1089 1090 1091 1092
            break;
        default:
            break;
        }

1093
        prefixCommandCount--;
1094
    }
1095

1096 1097 1098 1099 1100 1101 1102 1103
    // 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);

1104
    // Send to vehicle
1105
    _clearAndDeleteWriteMissionItems();
1106
    for (int i=0; i<resumeMission.count(); i++) {
1107
        _writeMissionItems.append(new MissionItem(*resumeMission[i], this));
1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124
    }
    _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();
}
1125 1126 1127 1128 1129 1130 1131 1132 1133


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