MissionManager.cc 19.7 KB
Newer Older
Don Gagne's avatar
Don Gagne committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "MissionManager.h"
#include "Vehicle.h"
29
#include "FirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
30
#include "MAVLinkProtocol.h"
31
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
32 33 34 35

QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")

MissionManager::MissionManager(Vehicle* vehicle)
36
    : _vehicle(vehicle)
37
    , _dedicatedLink(NULL)
Don Gagne's avatar
Don Gagne committed
38 39
    , _ackTimeoutTimer(NULL)
    , _retryAck(AckNone)
40 41
    , _readTransactionInProgress(false)
    , _writeTransactionInProgress(false)
42
    , _currentMissionItem(-1)
Don Gagne's avatar
Don Gagne committed
43 44 45 46 47 48 49 50 51 52
{
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
    
    _ackTimeoutTimer = new QTimer(this);
    _ackTimeoutTimer->setSingleShot(true);
    _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
    
    connect(_ackTimeoutTimer, &QTimer::timeout, this, &MissionManager::_ackTimeout);
}

53
MissionManager::~MissionManager()
Don Gagne's avatar
Don Gagne committed
54
{
55

Don Gagne's avatar
Don Gagne committed
56 57
}

58
void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
Don Gagne's avatar
Don Gagne committed
59
{
60 61
    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();

Don Gagne's avatar
Don Gagne committed
62
    _missionItems.clear();
63 64

    int firstIndex = skipFirstItem ? 1 : 0;
Don Gagne's avatar
Don Gagne committed
65
    
66
    for (int i=firstIndex; i<missionItems.count(); i++) {
67 68
        MissionItem* item = new MissionItem(*missionItems[i]);
        _missionItems.append(item);
69

70
        item->setIsCurrentItem(i == firstIndex);
71

72
        if (skipFirstItem) {
73
            // Home is in sequence 0, remainder of items start at sequence 1
74 75 76 77
            item->setSequenceNumber(item->sequenceNumber() - 1);
            if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                item->setParam1((int)item->param1() - 1);
            }
Don Gagne's avatar
Don Gagne committed
78 79
        }
    }
80
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
81

82 83 84 85 86 87
    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
    
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
        return;
    }
Don Gagne's avatar
Don Gagne committed
88

89 90 91 92 93 94
    // Prime write list
    for (int i=0; i<_missionItems.count(); i++) {
        _itemIndicesToWrite << i;
    }
    _writeTransactionInProgress = true;

95 96
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
97

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

102
    mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount);
103

104 105
    _dedicatedLink = _vehicle->priorityLink();
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
106
    _startAckTimeout(AckMissionRequest);
107
    emit inProgressChanged(true);
108 109
}

110
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
111
{
Don Gagne's avatar
Don Gagne committed
112
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
Don Gagne's avatar
Don Gagne committed
113 114 115 116
    
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
    
117 118 119
    _requestItemRetryCount = 0;
    _itemIndicesToRead.clear();
    _readTransactionInProgress = true;
Don Gagne's avatar
Don Gagne committed
120 121 122 123 124
    _clearMissionItems();
    
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
    
125
    mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request);
Don Gagne's avatar
Don Gagne committed
126
    
127 128
    _dedicatedLink = _vehicle->priorityLink();
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
129 130 131 132
    _startAckTimeout(AckMissionCount);
    emit inProgressChanged(true);
}

Don Gagne's avatar
Don Gagne committed
133 134
void MissionManager::_ackTimeout(void)
{
135 136 137 138 139
    AckType_t timedOutAck = _retryAck;
    
    _retryAck = AckNone;
    
    if (timedOutAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
140
        qCWarning(MissionManagerLog) << "_ackTimeout timeout with AckNone";
141
        _sendError(InternalError, "Internal error occured during Mission Item communication: _ackTimeOut:_retryAck == AckNone");
Don Gagne's avatar
Don Gagne committed
142 143 144
        return;
    }
    
145 146
    _sendError(AckTimeoutError, QString("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(timedOutAck)));
    _finishTransaction(false);
Don Gagne's avatar
Don Gagne committed
147 148
}

149
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
150 151 152 153 154 155 156
{
    _retryAck = ack;
    _ackTimeoutTimer->start();
}

bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
{
157 158 159 160
    bool        success = false;
    AckType_t   savedRetryAck = _retryAck;
    
    _retryAck = AckNone;
Don Gagne's avatar
Don Gagne committed
161 162 163
    
    _ackTimeoutTimer->stop();
    
164
    if (savedRetryAck != expectedAck) {
165 166
        _sendError(ProtocolOrderError, QString("Vehicle responded incorrectly to mission item protocol sequence: %1:%2").arg(_ackTypeToString(savedRetryAck)).arg(_ackTypeToString(expectedAck)));
        _finishTransaction(false);
Don Gagne's avatar
Don Gagne committed
167 168 169 170 171 172 173 174
        success = false;
    } else {
        success = true;
    }
    
    return success;
}

175
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
176
{
177
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
178 179 180 181 182 183 184 185
    
    mavlink_message_t       message;
    mavlink_mission_ack_t   missionAck;
    
    missionAck.target_system =      _vehicle->id();
    missionAck.target_component =   MAV_COMP_ID_MISSIONPLANNER;
    missionAck.type =               MAV_MISSION_ACCEPTED;
    
186
    mavlink_msg_mission_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionAck);
Don Gagne's avatar
Don Gagne committed
187
    
188 189
    _vehicle->sendMessageOnLink(_dedicatedLink, message);

190
    _finishTransaction(true);
Don Gagne's avatar
Don Gagne committed
191
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
192 193 194 195 196 197 198 199 200 201 202
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
    if (!_stopAckTimeout(AckMissionCount)) {
        return;
    }
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
203 204 205
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << missionCount.count;

    if (missionCount.count == 0) {
206
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
207
    } else {
208 209 210 211 212
        // Prime read list
        for (int i=0; i<missionCount.count; i++) {
            _itemIndicesToRead << i;
        }
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
213
    }
214 215

    
Don Gagne's avatar
Don Gagne committed
216 217
}

218
void MissionManager::_requestNextMissionItem(void)
Don Gagne's avatar
Don Gagne committed
219
{
220 221 222 223
    qCDebug(MissionManagerLog) << "_requestNextMissionItem sequenceNumber:" << _itemIndicesToRead[0];

    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
224 225 226 227 228 229 230 231
        return;
    }
    
    mavlink_message_t           message;
    mavlink_mission_request_t   missionRequest;
    
    missionRequest.target_system =      _vehicle->id();
    missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
232
    missionRequest.seq =                _itemIndicesToRead[0];
Don Gagne's avatar
Don Gagne committed
233
    
234
    mavlink_msg_mission_request_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionRequest);
Don Gagne's avatar
Don Gagne committed
235
    
236
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
237
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
238 239 240 241 242 243 244 245 246 247 248 249 250 251
}

void MissionManager::_handleMissionItem(const mavlink_message_t& message)
{
    mavlink_mission_item_t missionItem;
    
    if (!_stopAckTimeout(AckMissionItem)) {
        return;
    }
    
    mavlink_msg_mission_item_decode(&message, &missionItem);
    
    qCDebug(MissionManagerLog) << "_handleMissionItem sequenceNumber:" << missionItem.seq;
    
252 253 254 255
    if (_itemIndicesToRead.contains(missionItem.seq)) {
        _requestItemRetryCount = 0;
        _itemIndicesToRead.removeOne(missionItem.seq);

256
        MissionItem* item = new MissionItem(missionItem.seq,
257 258 259 260 261 262 263 264 265 266 267 268
                                            (MAV_CMD)missionItem.command,
                                            (MAV_FRAME)missionItem.frame,
                                            missionItem.param1,
                                            missionItem.param2,
                                            missionItem.param3,
                                            missionItem.param4,
                                            missionItem.x,
                                            missionItem.y,
                                            missionItem.z,
                                            missionItem.autocontinue,
                                            missionItem.current,
                                            this);
Don Gagne's avatar
Don Gagne committed
269

270
        if (item->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
271 272 273 274
            // Home is in position 0
            item->setParam1((int)item->param1() + 1);
        }

275 276 277 278 279 280 281
        _missionItems.append(item);
    } else {
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received item index which was not requested, disregrarding:" << missionItem.seq;
        if (++_requestItemRetryCount > _maxRetryCount) {
            _sendError(RequestRangeError, QString("Vehicle would not send item %1 after max retries. Read from Vehicle failed.").arg(_itemIndicesToRead[0]));
            _finishTransaction(false);
            return;
282
        }
Don Gagne's avatar
Don Gagne committed
283
    }
284 285
    
    if (_itemIndicesToRead.count() == 0) {
286
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
287
    } else {
288
        _requestNextMissionItem();
Don Gagne's avatar
Don Gagne committed
289 290 291 292 293
    }
}

void MissionManager::_clearMissionItems(void)
{
294
    _itemIndicesToRead.clear();
Don Gagne's avatar
Don Gagne committed
295 296 297 298 299 300 301 302 303 304 305 306 307 308 309
    _missionItems.clear();
}

void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
{
    mavlink_mission_request_t missionRequest;
    
    if (!_stopAckTimeout(AckMissionRequest)) {
        return;
    }
    
    mavlink_msg_mission_request_decode(&message, &missionRequest);
    
    qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:" << missionRequest.seq;
    
310 311 312 313 314 315 316
    if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
        if (missionRequest.seq > _missionItems.count()) {
            _sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_missionItems.count()).arg(missionRequest.seq));
            _finishTransaction(false);
            return;
        } else {
            qCDebug(MissionManagerLog) << "_handleMissionRequest sequence number requested which has already been sent, sending again:" << missionRequest.seq;
317
        }
318 319
    } else {
        _itemIndicesToWrite.removeOne(missionRequest.seq);
Don Gagne's avatar
Don Gagne committed
320 321 322 323 324
    }
    
    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;
    
325
    MissionItem* item = _missionItems[missionRequest.seq];
Don Gagne's avatar
Don Gagne committed
326 327 328 329 330 331 332 333 334
    
    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();
335 336 337
    missionItem.x =                 item->param5();
    missionItem.y =                 item->param6();
    missionItem.z =                 item->param7();
Don Gagne's avatar
Don Gagne committed
338 339 340 341
    missionItem.frame =             item->frame();
    missionItem.current =           missionRequest.seq == 0;
    missionItem.autocontinue =      item->autoContinue();
    
342
    mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem);
Don Gagne's avatar
Don Gagne committed
343
    
344
    _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
345
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
346 347 348 349 350 351
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
DonLakeFlyer's avatar
DonLakeFlyer committed
352
    // Save the retry ack before calling _stopAckTimeout since we'll need it to determine what
353 354 355 356 357 358 359
    // type of a protocol sequence we are in.
    AckType_t savedRetryAck = _retryAck;
    
    // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
    // a protocol sequence error. Call _stopAckTimeout with _retryAck so it will succeed no
    // matter what.
    if (!_stopAckTimeout(_retryAck)) {
Don Gagne's avatar
Don Gagne committed
360 361 362 363 364
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
365
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
366 367 368 369

    switch (savedRetryAck) {
        case AckNone:
            // State machine is idle. Vehicle is confused.
Don Gagne's avatar
Don Gagne committed
370
            _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
371 372 373
            break;
        case AckMissionCount:
            // MISSION_COUNT message expected
374 375
            _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
376 377 378
            break;
        case AckMissionItem:
            // MISSION_ITEM expected
379 380
            _sendError(VehicleError, QString("Vehicle returned error: %1. Partial list of mission items may have been returned.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
            _finishTransaction(false);
381 382 383 384
            break;
        case AckMissionRequest:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
385
                if (_itemIndicesToWrite.count() == 0) {
386
                    qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
387
                    _finishTransaction(true);
388
                } else {
389 390
                    _sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence, missed count %1. Vehicle only has partial list of mission items.").arg(_itemIndicesToWrite.count()));
                    _finishTransaction(false);
391 392
                }
            } else {
393 394
                _sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
                _finishTransaction(false);
395 396
            }
            break;
Don Gagne's avatar
Don Gagne committed
397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424
    }
}

/// Called when a new mavlink message for out vehicle is received
void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
        case MAVLINK_MSG_ID_MISSION_COUNT:
            _handleMissionCount(message);
            break;

        case MAVLINK_MSG_ID_MISSION_ITEM:
            _handleMissionItem(message);
            break;
            
        case MAVLINK_MSG_ID_MISSION_REQUEST:
            _handleMissionRequest(message);
            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:
425
            _handleMissionCurrent(message);
Don Gagne's avatar
Don Gagne committed
426 427 428 429
            break;
    }
}

430 431
void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
432
    qCDebug(MissionManagerLog) << "Sending error" << errorCode << errorMsg;
433

434
    emit error(errorCode, errorMsg);
435
}
Don Gagne's avatar
Don Gagne committed
436 437 438 439 440 441 442 443 444 445 446 447

QString MissionManager::_ackTypeToString(AckType_t ackType)
{
    switch (ackType) {
        case AckNone:   // State machine is idle
            return QString("No Ack");
        case AckMissionCount:   // MISSION_COUNT message expected
            return QString("MISSION_COUNT");
        case AckMissionItem:  ///< MISSION_ITEM expected
            return QString("MISSION_ITEM");
        case AckMissionRequest: ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            return QString("MISSION_REQUEST");
Don Gagne's avatar
Don Gagne committed
448 449
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
450
            return QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
451
    }    
Don Gagne's avatar
Don Gagne committed
452
}
Don Gagne's avatar
Don Gagne committed
453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505

QString MissionManager::_missionResultToString(MAV_MISSION_RESULT result)
{
    switch (result) {
        case MAV_MISSION_ACCEPTED:
            return QString("Mission accepted (MAV_MISSION_ACCEPTED)");
            break;
        case MAV_MISSION_ERROR:
            return QString("Unspecified error (MAV_MISSION_ERROR)");
            break;
        case MAV_MISSION_UNSUPPORTED_FRAME:
            return QString("Coordinate frame is not supported (MAV_MISSION_UNSUPPORTED_FRAME)");
            break;
        case MAV_MISSION_UNSUPPORTED:
            return QString("Command is not supported (MAV_MISSION_UNSUPPORTED)");
            break;
        case MAV_MISSION_NO_SPACE:
            return QString("Mission item exceeds storage space (MAV_MISSION_NO_SPACE)");
            break;
        case MAV_MISSION_INVALID:
            return QString("One of the parameters has an invalid value (MAV_MISSION_INVALID)");
            break;
        case MAV_MISSION_INVALID_PARAM1:
            return QString("Param1 has an invalid value (MAV_MISSION_INVALID_PARAM1)");
            break;
        case MAV_MISSION_INVALID_PARAM2:
            return QString("Param2 has an invalid value (MAV_MISSION_INVALID_PARAM2)");
            break;
        case MAV_MISSION_INVALID_PARAM3:
            return QString("param3 has an invalid value (MAV_MISSION_INVALID_PARAM3)");
            break;
        case MAV_MISSION_INVALID_PARAM4:
            return QString("Param4 has an invalid value (MAV_MISSION_INVALID_PARAM4)");
            break;
        case MAV_MISSION_INVALID_PARAM5_X:
            return QString("X/Param5 has an invalid value (MAV_MISSION_INVALID_PARAM5_X)");
            break;
        case MAV_MISSION_INVALID_PARAM6_Y:
            return QString("Y/Param6 has an invalid value (MAV_MISSION_INVALID_PARAM6_Y)");
            break;
        case MAV_MISSION_INVALID_PARAM7:
            return QString("Param7 has an invalid value (MAV_MISSION_INVALID_PARAM7)");
            break;
        case MAV_MISSION_INVALID_SEQUENCE:
            return QString("Received mission item out of sequence (MAV_MISSION_INVALID_SEQUENCE)");
            break;
        case MAV_MISSION_DENIED:
            return QString("Not accepting any mission commands (MAV_MISSION_DENIED)");
            break;
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
            return QString("QGC Internal Error");
    }
506
}
507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527

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

    _readTransactionInProgress = false;
    _writeTransactionInProgress = false;
    _itemIndicesToRead.clear();
    _itemIndicesToWrite.clear();

    emit inProgressChanged(false);
}

bool MissionManager::inProgress(void)
{
    return _readTransactionInProgress || _writeTransactionInProgress;
}
528 529 530 531 532 533 534 535 536 537 538 539 540

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

    mavlink_msg_mission_current_decode(&message, &missionCurrent);

    qCDebug(MissionManagerLog) << "_handleMissionCurrent seq:" << missionCurrent.seq;
    if (missionCurrent.seq != _currentMissionItem) {
        _currentMissionItem = missionCurrent.seq;
        emit currentItemChanged(_currentMissionItem);
    }
}