MissionManager.cc 22.3 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 31 32 33 34
#include "MAVLinkProtocol.h"

QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")

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

50
MissionManager::~MissionManager()
Don Gagne's avatar
Don Gagne committed
51
{
52

Don Gagne's avatar
Don Gagne committed
53 54
}

55
void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
Don Gagne's avatar
Don Gagne committed
56
{
57 58
    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();

59
    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
60
    _missionItems.clear();
61 62

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

        MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));

69 70 71 72 73 74
        if (skipFirstItem) {
            // Home is in sequence 1, remainder of items start at sequence 1
            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
75 76
        }
    }
77
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
78

79 80 81 82 83 84 85 86 87 88
    qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count();
    
    if (inProgress()) {
        qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress";
        return;
    }
    
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
    
89 90
    _expectedSequenceNumber = 0;
    
91 92 93 94 95 96 97
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
    
    mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount);
    
    _vehicle->sendMessage(message);
98
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
99
    emit inProgressChanged(true);
Don Gagne's avatar
Don Gagne committed
100 101
}

102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
void MissionManager::_retryWrite(void)
{
    qCDebug(MissionManagerLog) << "_retryWrite";
    
    mavlink_message_t       message;
    mavlink_mission_count_t missionCount;
    
    _expectedSequenceNumber = 0;
    
    missionCount.target_system = _vehicle->id();
    missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
    missionCount.count = _missionItems.count();
    
    mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount);
    
    _vehicle->sendMessage(message);
    _startAckTimeout(AckMissionRequest);
}

121
void MissionManager::requestMissionItems(void)
Don Gagne's avatar
Don Gagne committed
122
{
Don Gagne's avatar
Don Gagne committed
123
    qCDebug(MissionManagerLog) << "requestMissionItems read sequence";
Don Gagne's avatar
Don Gagne committed
124 125 126 127
    
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
    
128
    _retryCount = 0;
Don Gagne's avatar
Don Gagne committed
129 130 131 132 133 134 135 136
    _clearMissionItems();
    
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
    
    mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &request);
    
    _vehicle->sendMessage(message);
137 138 139 140 141 142 143 144 145 146 147
    _startAckTimeout(AckMissionCount);
    emit inProgressChanged(true);
}

void MissionManager::_retryRead(void)
{
    qCDebug(MissionManagerLog) << "_retryRead";
    
    mavlink_message_t               message;
    mavlink_mission_request_list_t  request;
    
148 149
    _clearMissionItems();
    
150 151 152 153 154 155 156
    request.target_system = _vehicle->id();
    request.target_component = MAV_COMP_ID_MISSIONPLANNER;
    
    mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &request);
    
    _vehicle->sendMessage(message);
    _startAckTimeout(AckMissionCount);
Don Gagne's avatar
Don Gagne committed
157 158 159 160
}

void MissionManager::_ackTimeout(void)
{
161 162 163 164 165
    AckType_t timedOutAck = _retryAck;
    
    _retryAck = AckNone;
    
    if (timedOutAck == AckNone) {
Don Gagne's avatar
Don Gagne committed
166
        qCWarning(MissionManagerLog) << "_ackTimeout timeout with AckNone";
167
        _sendError(InternalError, "Internal error occured during Mission Item communication: _ackTimeOut:_retryAck == AckNone");
Don Gagne's avatar
Don Gagne committed
168 169 170
        return;
    }
    
171
    if (!_retrySequence(timedOutAck)) {
Don Gagne's avatar
Don Gagne committed
172 173
        qCDebug(MissionManagerLog) << "_ackTimeout failed after max retries _retryAck:_retryCount" << _ackTypeToString(timedOutAck) << _retryCount;
        _sendError(AckTimeoutError, QString("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(timedOutAck)));
Don Gagne's avatar
Don Gagne committed
174 175 176
    }
}

177
void MissionManager::_startAckTimeout(AckType_t ack)
Don Gagne's avatar
Don Gagne committed
178 179 180 181 182 183 184
{
    _retryAck = ack;
    _ackTimeoutTimer->start();
}

bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
{
185 186 187 188
    bool        success = false;
    AckType_t   savedRetryAck = _retryAck;
    
    _retryAck = AckNone;
Don Gagne's avatar
Don Gagne committed
189 190 191
    
    _ackTimeoutTimer->stop();
    
192
    if (savedRetryAck != expectedAck) {
Don Gagne's avatar
Don Gagne committed
193
        qCDebug(MissionManagerLog) << "Invalid ack sequence _retryAck:expectedAck" << _ackTypeToString(savedRetryAck) << _ackTypeToString(expectedAck);
194 195
        
        if (_retrySequence(expectedAck)) {
Don Gagne's avatar
Don Gagne committed
196
            _sendError(ProtocolOrderError, QString("Vehicle responded incorrectly to mission item protocol sequence: %1:%2").arg(_ackTypeToString(savedRetryAck)).arg(_ackTypeToString(expectedAck)));
197
        }
Don Gagne's avatar
Don Gagne committed
198 199 200 201 202 203 204 205
        success = false;
    } else {
        success = true;
    }
    
    return success;
}

206
void MissionManager::_readTransactionComplete(void)
Don Gagne's avatar
Don Gagne committed
207
{
208
    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
Don Gagne's avatar
Don Gagne committed
209 210 211 212 213 214 215 216 217 218 219 220 221
    
    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;
    
    mavlink_msg_mission_ack_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionAck);
    
    _vehicle->sendMessage(message);
    
    emit newMissionItemsAvailable();
Don Gagne's avatar
Don Gagne committed
222
    emit inProgressChanged(false);
Don Gagne's avatar
Don Gagne committed
223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238
}

void MissionManager::_handleMissionCount(const mavlink_message_t& message)
{
    mavlink_mission_count_t missionCount;
    
    if (!_stopAckTimeout(AckMissionCount)) {
        return;
    }
    
    mavlink_msg_mission_count_decode(&message, &missionCount);
    
    _cMissionItems = missionCount.count;
    qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems;
    
    if (_cMissionItems == 0) {
239
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
240 241 242 243 244 245 246 247 248 249 250
    } else {
        _requestNextMissionItem(0);
    }
}

void MissionManager::_requestNextMissionItem(int sequenceNumber)
{
    qCDebug(MissionManagerLog) << "_requestNextMissionItem sequenceNumber:" << sequenceNumber;
    
    if (sequenceNumber >= _cMissionItems) {
        qCWarning(MissionManagerLog) << "_requestNextMissionItem requested seqeuence number > item count sequenceNumber::_cMissionItems" << sequenceNumber << _cMissionItems;
251
        _sendError(InternalError, QString("QGroundControl requested mission item outside of range (internal error): %1:%2").arg(sequenceNumber).arg(_cMissionItems));
Don Gagne's avatar
Don Gagne committed
252 253 254 255 256 257 258 259 260 261 262 263 264 265
        return;
    }
    
    mavlink_message_t           message;
    mavlink_mission_request_t   missionRequest;
    
    missionRequest.target_system =      _vehicle->id();
    missionRequest.target_component =   MAV_COMP_ID_MISSIONPLANNER;
    missionRequest.seq =                sequenceNumber;
    _expectedSequenceNumber =           sequenceNumber;
    
    mavlink_msg_mission_request_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionRequest);
    
    _vehicle->sendMessage(message);
266
    _startAckTimeout(AckMissionItem);
Don Gagne's avatar
Don Gagne committed
267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282
}

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;
    
    if (missionItem.seq != _expectedSequenceNumber) {
        qCDebug(MissionManagerLog) << "_handleMissionItem mission item received out of sequence expected:actual" << _expectedSequenceNumber << missionItem.seq;
283 284 285
        if (!_retrySequence(AckMissionItem)) {
            _sendError(ItemMismatchError, QString("Vehicle returned incorrect mission item: %1:%2").arg(_expectedSequenceNumber).arg(missionItem.seq));
        }
Don Gagne's avatar
Don Gagne committed
286 287 288 289 290 291
        return;
    }
        
    MissionItem* item = new MissionItem(this,
                                        missionItem.seq,
                                        QGeoCoordinate(missionItem.x, missionItem.y, missionItem.z),
Don Gagne's avatar
Don Gagne committed
292
                                        missionItem.command,
Don Gagne's avatar
Don Gagne committed
293 294 295
                                        missionItem.param1,
                                        missionItem.param2,
                                        missionItem.param3,
Don Gagne's avatar
Don Gagne committed
296
                                        missionItem.param4,
Don Gagne's avatar
Don Gagne committed
297 298
                                        missionItem.autocontinue,
                                        missionItem.current,
Don Gagne's avatar
Don Gagne committed
299
                                        missionItem.frame);
Don Gagne's avatar
Don Gagne committed
300 301
    _missionItems.append(item);
    
Don Gagne's avatar
Don Gagne committed
302 303 304 305 306
    if (!item->canEdit()) {
        _canEdit = false;
        emit canEditChanged(false);
    }
    
Don Gagne's avatar
Don Gagne committed
307 308
    int nextSequenceNumber = missionItem.seq + 1;
    if (nextSequenceNumber == _cMissionItems) {
309
        _readTransactionComplete();
Don Gagne's avatar
Don Gagne committed
310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332
    } else {
        _requestNextMissionItem(nextSequenceNumber);
    }
}

void MissionManager::_clearMissionItems(void)
{
    _cMissionItems = 0;
    _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;
    
333 334 335 336 337 338
    if (missionRequest.seq != _expectedSequenceNumber) {
        qCDebug(MissionManagerLog) << "_handleMissionRequest invalid sequence number requested: _expectedSequenceNumber:missionRequest.seq" << _expectedSequenceNumber << missionRequest.seq;
        
        if (!_retrySequence(AckMissionRequest)) {
            _sendError(ItemMismatchError, QString("Vehicle requested incorrect mission item: %1:%2").arg(_expectedSequenceNumber).arg(missionRequest.seq));
        }
Don Gagne's avatar
Don Gagne committed
339 340 341
        return;
    }
    
342 343
    _expectedSequenceNumber++;
    
Don Gagne's avatar
Don Gagne committed
344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366
    mavlink_message_t       messageOut;
    mavlink_mission_item_t  missionItem;
    
    MissionItem* item = (MissionItem*)_missionItems[missionRequest.seq];
    
    missionItem.target_system =     _vehicle->id();
    missionItem.target_component =  MAV_COMP_ID_MISSIONPLANNER;
    missionItem.seq =               missionRequest.seq;
    missionItem.command =           item->command();
    missionItem.x =                 item->coordinate().latitude();
    missionItem.y =                 item->coordinate().longitude();
    missionItem.z =                 item->coordinate().altitude();
    missionItem.param1 =            item->param1();
    missionItem.param2 =            item->param2();
    missionItem.param3 =            item->param3();
    missionItem.param4 =            item->param4();
    missionItem.frame =             item->frame();
    missionItem.current =           missionRequest.seq == 0;
    missionItem.autocontinue =      item->autoContinue();
    
    mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &messageOut, &missionItem);
    
    _vehicle->sendMessage(messageOut);
367
    _startAckTimeout(AckMissionRequest);
Don Gagne's avatar
Don Gagne committed
368 369 370 371 372 373
}

void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{
    mavlink_mission_ack_t missionAck;
    
374 375 376 377 378 379 380 381
    // Save th retry ack before calling _stopAckTimeout since we'll need it to determine what
    // 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
382 383 384 385 386
        return;
    }
    
    mavlink_msg_mission_ack_decode(&message, &missionAck);
    
Don Gagne's avatar
Don Gagne committed
387
    qCDebug(MissionManagerLog) << "_handleMissionAck type:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
388 389 390 391

    switch (savedRetryAck) {
        case AckNone:
            // State machine is idle. Vehicle is confused.
Don Gagne's avatar
Don Gagne committed
392
            qCDebug(MissionManagerLog) << "_handleMissionAck vehicle sent ack while state machine is idle: error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
Don Gagne's avatar
Don Gagne committed
393
            _sendError(VehicleError, QString("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
394 395 396
            break;
        case AckMissionCount:
            // MISSION_COUNT message expected
Don Gagne's avatar
Don Gagne committed
397
            qCDebug(MissionManagerLog) << "_handleMissionAck vehicle sent ack when MISSION_COUNT expected: error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
398
            if (!_retrySequence(AckMissionCount)) {
Don Gagne's avatar
Don Gagne committed
399
                _sendError(VehicleError, QString("Vehicle returned error: %1. Partial list of mission items may have been returned.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
400
            }
401 402 403
            break;
        case AckMissionItem:
            // MISSION_ITEM expected
Don Gagne's avatar
Don Gagne committed
404
            qCDebug(MissionManagerLog) << "_handleMissionAck vehicle sent ack when MISSION_ITEM expected: error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
405
            if (!_retrySequence(AckMissionItem)) {
Don Gagne's avatar
Don Gagne committed
406
                _sendError(VehicleError, QString("Vehicle returned error: %1. Partial list of mission items may have been returned.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
407 408 409 410 411 412 413 414 415 416 417 418 419 420 421
            }
            break;
        case AckMissionRequest:
            // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
            if (missionAck.type == MAV_MISSION_ACCEPTED) {
                if (_expectedSequenceNumber == _missionItems.count()) {
                    qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
                    emit inProgressChanged(false);
                } else {
                    qCDebug(MissionManagerLog) << "_handleMissionAck vehicle did not reqeust all items: _expectedSequenceNumber:_missionItems.count" << _expectedSequenceNumber << _missionItems.count();
                    if (!_retrySequence(AckMissionRequest)) {
                        _sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence %1:%2. Vehicle only has partial list of mission items.").arg(_expectedSequenceNumber).arg(_missionItems.count()));
                    }
                }
            } else {
Don Gagne's avatar
Don Gagne committed
422
                qCDebug(MissionManagerLog) << "_handleMissionAck ack error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
423
                if (!_retrySequence(AckMissionRequest)) {
Don Gagne's avatar
Don Gagne committed
424
                    _sendError(VehicleError, QString("Vehicle returned error: %1.  Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
425 426 427
                }
            }
            break;
Don Gagne's avatar
Don Gagne committed
428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470
    }
}

/// 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:
            // FIXME: NYI
            break;
    }
}

QmlObjectListModel* MissionManager::copyMissionItems(void)
{
    QmlObjectListModel* list = new QmlObjectListModel();
    
    for (int i=0; i<_missionItems.count(); i++) {
        list->append(new MissionItem(*qobject_cast<const MissionItem*>(_missionItems[i])));
    }
    
    return list;
}
471 472 473 474 475 476 477 478 479 480 481

void MissionManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
{
    emit inProgressChanged(false);
    emit error(errorCode, errorMsg);
}

/// Retry the protocol sequence given the specified ack
/// @return true: sequence retried, false: out of retries
bool MissionManager::_retrySequence(AckType_t ackType)
{
Don Gagne's avatar
Don Gagne committed
482
    qCDebug(MissionManagerLog) << "_retrySequence ackType:" << _ackTypeToString(ackType) << "_retryCount" << _retryCount;
483
    
484 485 486 487
    switch (ackType) {
        case AckMissionCount:
        case AckMissionItem:
            if (++_retryCount <= _maxRetryCount) {
488 489 490
                // We are in the middle of a read sequence, start over
                _retryRead();
                return true;
491 492 493 494 495 496 497 498
            } else {
                // Read sequence failed, signal for what we have up to this point
                emit newMissionItemsAvailable();
                return false;
            }
            break;
        case AckMissionRequest:
            if (++_retryCount <= _maxRetryCount) {
499 500 501
                // We are in the middle of a write sequence, start over
                _retryWrite();
                return true;
502
            } else {
503
                return false;
504 505 506
            }
            break;
        default:
Don Gagne's avatar
Don Gagne committed
507 508
            qCWarning(MissionManagerLog) << "_retrySequence fell through switch: ackType:" << _ackTypeToString(ackType);
            _sendError(InternalError, QString("Internal error occured during Mission Item communication: _retrySequence fell through switch: ackType:").arg(_ackTypeToString(ackType)));
509
            return false;
510 511
    }
}
Don Gagne's avatar
Don Gagne committed
512 513 514 515 516 517 518 519 520 521 522 523

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
524 525
        default:
            qWarning(MissionManagerLog) << "Fell off end of switch statement";
Don Gagne's avatar
Don Gagne committed
526
            return QString("QGC Internal Error");
Don Gagne's avatar
Don Gagne committed
527
    }    
Don Gagne's avatar
Don Gagne committed
528
}
Don Gagne's avatar
Don Gagne committed
529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581

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");
    }
582
}