MissionManagerTest.cc 19.1 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/>.
 
 ======================================================================*/

#include "MissionManagerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"

const MissionManagerTest::TestCase_t MissionManagerTest::_rgTestCases[] = {
29
    { "0\t0\t3\t16\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 0, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT,     10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
Don Gagne's avatar
Don Gagne committed
30
    { "1\t0\t3\t17\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_UNLIM, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
31 32 33 34 35
    { "2\t0\t3\t18\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 2, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TURNS, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
    { "3\t0\t3\t19\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 3, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TIME,  10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
    { "4\t0\t3\t21\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 4, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LAND,         10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
    { "5\t0\t3\t22\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 5, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_TAKEOFF,      10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
    { "6\t0\t2\t112\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 6, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_CONDITION_DELAY,  10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION } },
Don Gagne's avatar
Don Gagne committed
36
    { "7\t0\t2\t177\t3\t20\t30\t40\t-10\t-20\t-30\t1\r\n",  { 7, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_DO_JUMP,          3,    20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION } },
Don Gagne's avatar
Don Gagne committed
37
};
Don Gagne's avatar
Don Gagne committed
38
const size_t MissionManagerTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestCases[0]);
Don Gagne's avatar
Don Gagne committed
39 40 41 42 43 44

MissionManagerTest::MissionManagerTest(void)
{
    
}

45
void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly)
Don Gagne's avatar
Don Gagne committed
46
{
47 48 49 50 51 52
    _mockLink->setMissionItemFailureMode(failureMode, failFirstTimeOnly);
    if (failFirstTimeOnly) {
        // Should fail first time, then retry should succed
        failureMode = MockLinkMissionItemHandler::FailNone;
    }
    
Don Gagne's avatar
Don Gagne committed
53 54 55
    // Setup our test case data
    QmlObjectListModel* list = new QmlObjectListModel();
    
56 57 58 59 60 61 62 63 64 65
    // Editor has a home position item on the front, so we do the same
    MissionItem* homeItem = new MissionItem(this);
    homeItem->setHomePositionSpecialCase(true);
    homeItem->setHomePositionValid(false);
    homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    homeItem->setLatitude(47.3769);
    homeItem->setLongitude(8.549444);
    homeItem->setSequenceNumber(0);
    list->insert(0, homeItem);

Don Gagne's avatar
Don Gagne committed
66
    for (size_t i=0; i<_cTestCases; i++) {
Don Gagne's avatar
Don Gagne committed
67 68 69 70 71 72
        const TestCase_t* testCase = &_rgTestCases[i];
        
        MissionItem* item = new MissionItem(list);
        
        QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly);
        QVERIFY(item->load(loadStream));
73 74 75 76 77 78 79

        // Mission Manager expects to get 1-base sequence numbers for write

        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
80 81 82 83 84
        
        list->append(item);
    }
    
    // Send the items to the vehicle
Don Gagne's avatar
Don Gagne committed
85
    _missionManager->writeMissionItems(*list);
86
    
87 88 89
    // writeMissionItems should emit these signals before returning:
    //      inProgressChanged
    //      newMissionItemsAvailable
Don Gagne's avatar
Don Gagne committed
90
    QVERIFY(_missionManager->inProgress());
91
    QCOMPARE(_multiSpyMissionManager->checkSignalByMask(inProgressChangedSignalMask | newMissionItemsAvailableSignalMask), true);
Don Gagne's avatar
Don Gagne committed
92 93
    _checkInProgressValues(true);
    
94
    _multiSpyMissionManager->clearAllSignals();
Don Gagne's avatar
Don Gagne committed
95
    
96 97 98 99 100
    if (failureMode == MockLinkMissionItemHandler::FailNone) {
        // This should be clean run
        
        // Wait for write sequence to complete. We should get:
        //      inProgressChanged(false) signal
101 102
        _multiSpyMissionManager->waitForSignalByIndex(inProgressChangedSignalIndex, _missionManagerSignalWaitTime);
        QCOMPARE(_multiSpyMissionManager->checkOnlySignalByMask(inProgressChangedSignalMask), true);
103 104 105 106
        
        // Validate inProgressChanged signal value
        _checkInProgressValues(false);

Don Gagne's avatar
Don Gagne committed
107 108 109 110 111 112 113 114 115
        // Validate item count in mission manager

        int expectedCount = (int)_cTestCases;
        if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            // Home position at position 0 comes from vehicle
            expectedCount++;
        }

        QCOMPARE(_missionManager->missionItems()->count(), expectedCount);
116 117 118
    } else {
        // This should be a failed run
        
Don Gagne's avatar
Don Gagne committed
119 120
        setExpectedMessageBox(QMessageBox::Ok);

121 122 123
        // Wait for write sequence to complete. We should get:
        //      inProgressChanged(false) signal
        //      error(errorCode, QString) signal
124 125
        _multiSpyMissionManager->waitForSignalByIndex(inProgressChangedSignalIndex, _missionManagerSignalWaitTime);
        QCOMPARE(_multiSpyMissionManager->checkSignalByMask(inProgressChangedSignalMask | errorSignalMask), true);
126 127 128 129 130
        
        // Validate inProgressChanged signal value
        _checkInProgressValues(false);
        
        // Validate error signal values
131
        QSignalSpy* spy = _multiSpyMissionManager->getSpyByIndex(errorSignalIndex);
132 133 134 135 136
        QList<QVariant> signalArgs = spy->takeFirst();
        QCOMPARE(signalArgs.count(), 2);
        qDebug() << signalArgs[1].toString();
        QCOMPARE(signalArgs[0].toInt(), (int)errorCode);

Don Gagne's avatar
Don Gagne committed
137
        checkExpectedMessageBox();
138
    }
Don Gagne's avatar
Don Gagne committed
139 140 141 142 143
    
    QCOMPARE(_missionManager->canEdit(), true);
    
    delete list;
    list = NULL;
144
    _multiSpyMissionManager->clearAllSignals();
145 146
}

147
void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly)
148 149
{
    _writeItems(MockLinkMissionItemHandler::FailNone, MissionManager::InternalError, false);
Don Gagne's avatar
Don Gagne committed
150
    
151 152 153 154 155 156
    _mockLink->setMissionItemFailureMode(failureMode, failFirstTimeOnly);
    if (failFirstTimeOnly) {
        // Should fail first time, then retry should succed
        failureMode = MockLinkMissionItemHandler::FailNone;
    }

Don Gagne's avatar
Don Gagne committed
157 158 159 160 161
    // Read the items back from the vehicle
    _missionManager->requestMissionItems();
    
    // requestMissionItems should emit inProgressChanged signal before returning so no need to wait for it
    QVERIFY(_missionManager->inProgress());
162
    QCOMPARE(_multiSpyMissionManager->checkOnlySignalByMask(inProgressChangedSignalMask), true);
Don Gagne's avatar
Don Gagne committed
163 164
    _checkInProgressValues(true);
    
165
    _multiSpyMissionManager->clearAllSignals();
Don Gagne's avatar
Don Gagne committed
166
    
167 168 169 170 171 172
    if (failureMode == MockLinkMissionItemHandler::FailNone) {
        // This should be clean run
        
        // Now wait for read sequence to complete. We should get:
        //      inProgressChanged(false) signal to signal completion
        //      newMissionItemsAvailable signal
173 174 175
        _multiSpyMissionManager->waitForSignalByIndex(inProgressChangedSignalIndex, _missionManagerSignalWaitTime);
        QCOMPARE(_multiSpyMissionManager->checkSignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask), true);
        QCOMPARE(_multiSpyMissionManager->checkNoSignalByMask(canEditChangedSignalMask), true);
176
        _checkInProgressValues(false);
Don Gagne's avatar
Don Gagne committed
177

178 179 180
    } else {
        // This should be a failed run
        
Don Gagne's avatar
Don Gagne committed
181 182
        setExpectedMessageBox(QMessageBox::Ok);

183 184 185 186
        // Wait for read sequence to complete. We should get:
        //      inProgressChanged(false) signal to signal completion
        //      error(errorCode, QString) signal
        //      newMissionItemsAvailable signal
187 188
        _multiSpyMissionManager->waitForSignalByIndex(inProgressChangedSignalIndex, _missionManagerSignalWaitTime);
        QCOMPARE(_multiSpyMissionManager->checkSignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask | errorSignalMask), true);
189 190 191 192 193
        
        // Validate inProgressChanged signal value
        _checkInProgressValues(false);
        
        // Validate error signal values
194
        QSignalSpy* spy = _multiSpyMissionManager->getSpyByIndex(errorSignalIndex);
195 196 197 198
        QList<QVariant> signalArgs = spy->takeFirst();
        QCOMPARE(signalArgs.count(), 2);
        qDebug() << signalArgs[1].toString();
        QCOMPARE(signalArgs[0].toInt(), (int)errorCode);
Don Gagne's avatar
Don Gagne committed
199 200
        
        checkExpectedMessageBox();
201
    }
Don Gagne's avatar
Don Gagne committed
202
    
203
    _multiSpyMissionManager->clearAllSignals();
204 205

    // Validate returned items
Don Gagne's avatar
Don Gagne committed
206
    
207
    size_t cMissionItemsExpected;
Don Gagne's avatar
Don Gagne committed
208
    
209
    if (failureMode == MockLinkMissionItemHandler::FailNone || failFirstTimeOnly == true) {
Don Gagne's avatar
Don Gagne committed
210 211 212 213 214
        cMissionItemsExpected = (int)_cTestCases;
        if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            // Home position at position 0 comes from vehicle
            cMissionItemsExpected++;
        }
215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
    } else {
        switch (failureMode) {
            case MockLinkMissionItemHandler::FailReadRequestListNoResponse:
            case MockLinkMissionItemHandler::FailReadRequest0NoResponse:
            case MockLinkMissionItemHandler::FailReadRequest0IncorrectSequence:
            case MockLinkMissionItemHandler::FailReadRequest0ErrorAck:
                cMissionItemsExpected = 0;
                break;
            case MockLinkMissionItemHandler::FailReadRequest1NoResponse:
            case MockLinkMissionItemHandler::FailReadRequest1IncorrectSequence:
            case MockLinkMissionItemHandler::FailReadRequest1ErrorAck:
                cMissionItemsExpected = 1;
                break;
            default:
                // Internal error
                Q_ASSERT(false);
                break;
        }
    }
    
    QCOMPARE(_missionManager->missionItems()->count(), (int)cMissionItemsExpected);
    QCOMPARE(_missionManager->canEdit(), true);
Don Gagne's avatar
Don Gagne committed
237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259

    size_t firstActualItem = 0;
    if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        // First item is home position, don't validate it
        firstActualItem++;
    }

    int testCaseIndex = 0;
    for (size_t actualItemIndex=firstActualItem; actualItemIndex<cMissionItemsExpected; actualItemIndex++) {
        const TestCase_t* testCase = &_rgTestCases[testCaseIndex];

        int expectedSequenceNumber = testCase->expectedItem.sequenceNumber;
        int expectedParam1 = (int)testCase->expectedItem.param1;
        if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            // Account for home position in first item
            expectedSequenceNumber++;
            if (testCase->expectedItem.command == MAV_CMD_DO_JUMP) {
                // Expected data in test case is for PX4
                expectedParam1++;
            }
        }

        MissionItem* actual = qobject_cast<MissionItem*>(_missionManager->missionItems()->get(actualItemIndex));
Don Gagne's avatar
Don Gagne committed
260
        
Don Gagne's avatar
Don Gagne committed
261 262
        qDebug() << "Test case" << testCaseIndex;
        QCOMPARE(actual->sequenceNumber(),          expectedSequenceNumber);
Don Gagne's avatar
Don Gagne committed
263 264 265 266
        QCOMPARE(actual->coordinate().latitude(),   testCase->expectedItem.coordinate.latitude());
        QCOMPARE(actual->coordinate().longitude(),  testCase->expectedItem.coordinate.longitude());
        QCOMPARE(actual->coordinate().altitude(),   testCase->expectedItem.coordinate.altitude());
        QCOMPARE((int)actual->command(),       (int)testCase->expectedItem.command);
Don Gagne's avatar
Don Gagne committed
267
        QCOMPARE((int)actual->param1(),        (int)expectedParam1);
Don Gagne's avatar
Don Gagne committed
268 269 270 271 272
        QCOMPARE(actual->param2(),                  testCase->expectedItem.param2);
        QCOMPARE(actual->param3(),                  testCase->expectedItem.param3);
        QCOMPARE(actual->param4(),                  testCase->expectedItem.param4);
        QCOMPARE(actual->autoContinue(),            testCase->expectedItem.autocontinue);
        QCOMPARE(actual->frame(),                   testCase->expectedItem.frame);
Don Gagne's avatar
Don Gagne committed
273 274

        testCaseIndex++;
Don Gagne's avatar
Don Gagne committed
275
    }
276
    
Don Gagne's avatar
Don Gagne committed
277
}
278

Don Gagne's avatar
Don Gagne committed
279
void MissionManagerTest::_testWriteFailureHandlingWorker(void)
280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319
{
    /*
    /// Called to send a MISSION_ACK message while the MissionManager is in idle state
    void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
    
    /// Called to send a MISSION_ITEM message while the MissionManager is in idle state
    void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
    
    /// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
    void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
    */
    
    typedef struct {
        const char*                                 failureText;
        MockLinkMissionItemHandler::FailureMode_t   failureMode;
        MissionManager::ErrorCode_t                 errorCode;
    } TestCase_t;
    
    static const TestCase_t rgTestCases[] = {
        { "No Failure",                         MockLinkMissionItemHandler::FailNone,                           MissionManager::AckTimeoutError },
        { "FailWriteRequest0NoResponse",        MockLinkMissionItemHandler::FailWriteRequest0NoResponse,        MissionManager::AckTimeoutError },
        { "FailWriteRequest1NoResponse",        MockLinkMissionItemHandler::FailWriteRequest1NoResponse,        MissionManager::AckTimeoutError },
        { "FailWriteRequest0IncorrectSequence", MockLinkMissionItemHandler::FailWriteRequest0IncorrectSequence, MissionManager::ItemMismatchError },
        { "FailWriteRequest1IncorrectSequence", MockLinkMissionItemHandler::FailWriteRequest1IncorrectSequence, MissionManager::ItemMismatchError },
        { "FailWriteRequest0ErrorAck",          MockLinkMissionItemHandler::FailWriteRequest0ErrorAck,          MissionManager::VehicleError },
        { "FailWriteRequest1ErrorAck",          MockLinkMissionItemHandler::FailWriteRequest1ErrorAck,          MissionManager::VehicleError },
        { "FailWriteFinalAckNoResponse",        MockLinkMissionItemHandler::FailWriteFinalAckNoResponse,        MissionManager::AckTimeoutError },
        { "FailWriteFinalAckErrorAck",          MockLinkMissionItemHandler::FailWriteFinalAckErrorAck,          MissionManager::VehicleError },
        { "FailWriteFinalAckMissingRequests",   MockLinkMissionItemHandler::FailWriteFinalAckMissingRequests,   MissionManager::MissingRequestsError },
    };

    for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
        qDebug() << "TEST CASE " << rgTestCases[i].failureText << "errorCode:" << rgTestCases[i].errorCode << "failFirstTimeOnly:false";
        _writeItems(rgTestCases[i].failureMode, rgTestCases[i].errorCode, false);
        _mockLink->resetMissionItemHandler();
        qDebug() << "TEST CASE " << rgTestCases[i].failureText << "errorCode:" << rgTestCases[i].errorCode << "failFirstTimeOnly:true";
        _writeItems(rgTestCases[i].failureMode, rgTestCases[i].errorCode, true);
        _mockLink->resetMissionItemHandler();
    }
}
320

Don Gagne's avatar
Don Gagne committed
321
void MissionManagerTest::_testReadFailureHandlingWorker(void)
322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354
{
    /*
     /// Called to send a MISSION_ACK message while the MissionManager is in idle state
     void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) { _missionItemHandler.sendUnexpectedMissionAck(ackType); }
     
     /// Called to send a MISSION_ITEM message while the MissionManager is in idle state
     void sendUnexpectedMissionItem(void) { _missionItemHandler.sendUnexpectedMissionItem(); }
     
     /// Called to send a MISSION_REQUEST message while the MissionManager is in idle state
     void sendUnexpectedMissionRequest(void) { _missionItemHandler.sendUnexpectedMissionRequest(); }
     */
    
    typedef struct {
        const char*                                 failureText;
        MockLinkMissionItemHandler::FailureMode_t   failureMode;
        MissionManager::ErrorCode_t                 errorCode;
    } TestCase_t;
    
    static const TestCase_t rgTestCases[] = {
        { "No Failure",                         MockLinkMissionItemHandler::FailNone,                           MissionManager::AckTimeoutError },
        { "FailReadRequestListNoResponse",      MockLinkMissionItemHandler::FailReadRequestListNoResponse,      MissionManager::AckTimeoutError },
        { "FailReadRequest0NoResponse",         MockLinkMissionItemHandler::FailReadRequest0NoResponse,         MissionManager::AckTimeoutError },
        { "FailReadRequest1NoResponse",         MockLinkMissionItemHandler::FailReadRequest1NoResponse,         MissionManager::AckTimeoutError },
        { "FailReadRequest0IncorrectSequence",  MockLinkMissionItemHandler::FailReadRequest0IncorrectSequence,  MissionManager::ItemMismatchError },
        { "FailReadRequest1IncorrectSequence",  MockLinkMissionItemHandler::FailReadRequest1IncorrectSequence,  MissionManager::ItemMismatchError },
        { "FailReadRequest0ErrorAck",           MockLinkMissionItemHandler::FailReadRequest0ErrorAck,           MissionManager::VehicleError },
        { "FailReadRequest1ErrorAck",           MockLinkMissionItemHandler::FailReadRequest1ErrorAck,           MissionManager::VehicleError },
    };
    
    for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
        qDebug() << "TEST CASE " << rgTestCases[i].failureText << "errorCode:" << rgTestCases[i].errorCode << "failFirstTimeOnly:false";
        _roundTripItems(rgTestCases[i].failureMode, rgTestCases[i].errorCode, false);
        _mockLink->resetMissionItemHandler();
355
        _multiSpyMissionManager->clearAllSignals();
356 357 358
        qDebug() << "TEST CASE " << rgTestCases[i].failureText << "errorCode:" << rgTestCases[i].errorCode << "failFirstTimeOnly:true";
        _roundTripItems(rgTestCases[i].failureMode, rgTestCases[i].errorCode, true);
        _mockLink->resetMissionItemHandler();
359
        _multiSpyMissionManager->clearAllSignals();
360 361
    }
}
Don Gagne's avatar
Don Gagne committed
362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386

void MissionManagerTest::_testWriteFailureHandlingAPM(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    _testWriteFailureHandlingWorker();
}

void MissionManagerTest::_testReadFailureHandlingAPM(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    _testReadFailureHandlingWorker();
}


void MissionManagerTest::_testWriteFailureHandlingPX4(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_PX4);
    _testWriteFailureHandlingWorker();
}

void MissionManagerTest::_testReadFailureHandlingPX4(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_PX4);
    _testReadFailureHandlingWorker();
}