UnitTest.cc 16.7 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * 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 16 17

/// @file
///     @brief Base class for all unit tests
///
///     @author Don Gagne <don@thegagnes.com>

#include "UnitTest.h"
#include "QGCApplication.h"
18
#include "MAVLinkProtocol.h"
19
#include "Vehicle.h"
20 21
#include "AppSettings.h"
#include "SettingsManager.h"
Don Gagne's avatar
Don Gagne committed
22

23 24 25
#include <QTemporaryFile>
#include <QTime>

Don Gagne's avatar
Don Gagne committed
26 27 28 29 30
bool UnitTest::_messageBoxRespondedTo = false;
bool UnitTest::_badResponseButton = false;
QMessageBox::StandardButton UnitTest::_messageBoxResponseButton = QMessageBox::NoButton;
int UnitTest::_missedMessageBoxCount = 0;

31 32 33 34 35 36
bool UnitTest::_fileDialogRespondedTo = false;
bool UnitTest::_fileDialogResponseSet = false;
QStringList UnitTest::_fileDialogResponse;
enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileName;
int UnitTest::_missedFileDialogCount = 0;

37
UnitTest::UnitTest(void)
38 39 40 41
    : _linkManager(nullptr)
    , _mockLink(nullptr)
    , _mainWindow(nullptr)
    , _vehicle(nullptr)
42 43 44 45 46 47 48
    , _expectMissedFileDialog(false)
    , _expectMissedMessageBox(false)
    , _unitTestRun(false)
    , _initCalled(false)
    , _cleanupCalled(false)
{    

Don Gagne's avatar
Don Gagne committed
49 50 51 52 53 54 55 56 57 58 59 60 61
}

UnitTest::~UnitTest()
{
    if (_unitTestRun) {
        // Derived classes must call base class implementations
        Q_ASSERT(_initCalled);
        Q_ASSERT(_cleanupCalled);
    }
}

void UnitTest::_addTest(QObject* test)
{
Don Gagne's avatar
Don Gagne committed
62 63 64
	QList<QObject*>& tests = _testList();

    Q_ASSERT(!tests.contains(test));
Don Gagne's avatar
Don Gagne committed
65
    
Don Gagne's avatar
Don Gagne committed
66
    tests.append(test);
Don Gagne's avatar
Don Gagne committed
67 68 69 70 71 72 73
}

void UnitTest::_unitTestCalled(void)
{
    _unitTestRun = true;
}

Don Gagne's avatar
Don Gagne committed
74 75 76 77 78 79 80
/// @brief Returns the list of unit tests.
QList<QObject*>& UnitTest::_testList(void)
{
	static QList<QObject*> tests;
	return tests;
}

81
int UnitTest::run(QString& singleTest)
Don Gagne's avatar
Don Gagne committed
82 83 84
{
    int ret = 0;
    
85
    for (QObject* test: _testList()) {
Don Gagne's avatar
Don Gagne committed
86
        if (singleTest.isEmpty() || singleTest == test->objectName()) {
87 88 89
            QStringList args;
            args << "*" << "-maxwarnings" << "0";
            ret += QTest::qExec(test, args);
Don Gagne's avatar
Don Gagne committed
90 91 92 93 94 95 96 97 98 99 100
        }
    }
    
    return ret;
}

/// @brief Called before each test.
///         Make sure to call first in your derived class
void UnitTest::init(void)
{
    _initCalled = true;
101 102 103 104 105

    if (!_linkManager) {
        _linkManager = qgcApp()->toolbox()->linkManager();
        connect(_linkManager, &LinkManager::linkDeleted, this, &UnitTest::_linkDeleted);
    }
106 107

    _linkManager->restart();
108 109 110 111 112

    // Force offline vehicle back to defaults
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
    appSettings->offlineEditingFirmwareType()->setRawValue(appSettings->offlineEditingFirmwareType()->rawDefaultValue());
    appSettings->offlineEditingVehicleType()->setRawValue(appSettings->offlineEditingVehicleType()->rawDefaultValue());
Don Gagne's avatar
Don Gagne committed
113 114 115 116 117
    
    _messageBoxRespondedTo = false;
    _missedMessageBoxCount = 0;
    _badResponseButton = false;
    _messageBoxResponseButton = QMessageBox::NoButton;
118 119 120 121 122
    
    _fileDialogRespondedTo = false;
    _missedFileDialogCount = 0;
    _fileDialogResponseSet = false;
    _fileDialogResponse.clear();
Don Gagne's avatar
Don Gagne committed
123

124 125 126
    _expectMissedFileDialog = false;
    _expectMissedMessageBox = false;
    
127
    MAVLinkProtocol::deleteTempLogFiles();
Don Gagne's avatar
Don Gagne committed
128 129 130 131 132 133 134
}

/// @brief Called after each test.
///         Make sure to call first in your derived class
void UnitTest::cleanup(void)
{
    _cleanupCalled = true;
135

136 137 138
    _disconnectMockLink();
    _closeMainWindow();

139 140 141
    // We add a slight delay here to allow for deleteLater and Qml cleanup
    QTest::qWait(200);

142 143 144 145 146 147 148 149 150
    // Keep in mind that any code below these QCOMPARE may be skipped if the compare fails
    if (_expectMissedMessageBox) {
        QEXPECT_FAIL("", "Expecting failure due internal testing", Continue);
    }
    QCOMPARE(_missedMessageBoxCount, 0);
    if (_expectMissedFileDialog) {
        QEXPECT_FAIL("", "Expecting failure due internal testing", Continue);
    }
    QCOMPARE(_missedFileDialogCount, 0);
Don Gagne's avatar
Don Gagne committed
151 152 153 154
}

void UnitTest::setExpectedMessageBox(QMessageBox::StandardButton response)
{
155 156
    //-- TODO
#if 0
157
    // This means that there was an expected message box but no call to checkExpectedMessageBox
Don Gagne's avatar
Don Gagne committed
158 159 160 161 162
    Q_ASSERT(!_messageBoxRespondedTo);
    
    Q_ASSERT(response != QMessageBox::NoButton);
    Q_ASSERT(_messageBoxResponseButton == QMessageBox::NoButton);
    
163
    // Make sure we haven't missed any previous message boxes
Don Gagne's avatar
Don Gagne committed
164 165
    int missedMessageBoxCount = _missedMessageBoxCount;
    QCOMPARE(missedMessageBoxCount, 0);
166 167
#endif
    _missedMessageBoxCount = 0;
Don Gagne's avatar
Don Gagne committed
168 169 170
    _messageBoxResponseButton = response;
}

171 172
void UnitTest::setExpectedFileDialog(enum FileDialogType type, QStringList response)
{
173 174
    //-- TODO
#if 0
175 176 177 178 179 180 181 182 183 184
    // This means that there was an expected file dialog but no call to checkExpectedFileDialog
    Q_ASSERT(!_fileDialogRespondedTo);
    
    // Multiple responses must be expected getOpenFileNames
    Q_ASSERT(response.count() <= 1 || type == getOpenFileNames);

    // Make sure we haven't missed any previous file dialogs
    int missedFileDialogCount = _missedFileDialogCount;
    _missedFileDialogCount = 0;
    QCOMPARE(missedFileDialogCount, 0);
185
#endif
186 187 188 189 190
    _fileDialogResponseSet = true;
    _fileDialogResponse = response;
    _fileDialogExpectedType = type;
}

Don Gagne's avatar
Don Gagne committed
191 192 193 194 195 196 197 198 199 200 201 202
void UnitTest::checkExpectedMessageBox(int expectFailFlags)
{
    // Previous call to setExpectedMessageBox should have already checked this
    Q_ASSERT(_missedMessageBoxCount == 0);
    
    // Check for a valid response
    
    if (expectFailFlags & expectFailBadResponseButton) {
        QEXPECT_FAIL("", "Expecting failure due to bad button response", Continue);
    }
    QCOMPARE(_badResponseButton, false);
    
203
    if (expectFailFlags & expectFailNoDialog) {
Don Gagne's avatar
Don Gagne committed
204 205
        QEXPECT_FAIL("", "Expecting failure due to no message box", Continue);
    }
206 207 208
    
    // Clear this flag before QCOMPARE since anything after QCOMPARE will be skipped on failure
    
Gus Grubba's avatar
Gus Grubba committed
209 210 211 212
    //-- TODO
    // bool messageBoxRespondedTo = _messageBoxRespondedTo;
    // QCOMPARE(messageBoxRespondedTo, true);
    _messageBoxRespondedTo = false;
213 214
}

Don Gagne's avatar
Don Gagne committed
215 216 217 218 219 220 221
void UnitTest::checkMultipleExpectedMessageBox(int messageCount)
{
    int missedMessageBoxCount = _missedMessageBoxCount;
    _missedMessageBoxCount = 0;
    QCOMPARE(missedMessageBoxCount, messageCount);
}

222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240
void UnitTest::checkExpectedFileDialog(int expectFailFlags)
{
    // Internal testing
    
    if (expectFailFlags & expectFailNoDialog) {
        QEXPECT_FAIL("", "Expecting failure due to no file dialog", Continue);
    }
    if (expectFailFlags & expectFailWrongFileDialog) {
        QEXPECT_FAIL("", "Expecting failure due to incorrect file dialog", Continue);
    } else {
        // Previous call to setExpectedFileDialog should have already checked this
        Q_ASSERT(_missedFileDialogCount == 0);
    }
    
    // Clear this flag before QCOMPARE since anything after QCOMPARE will be skipped on failure
    bool fileDialogRespondedTo = _fileDialogRespondedTo;
    _fileDialogRespondedTo = false;
    
    QCOMPARE(fileDialogRespondedTo, true);
Don Gagne's avatar
Don Gagne committed
241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
}

QMessageBox::StandardButton UnitTest::_messageBox(QMessageBox::Icon icon, const QString& title, const QString& text, QMessageBox::StandardButtons buttons, QMessageBox::StandardButton defaultButton)
{
    QMessageBox::StandardButton retButton;
    
    Q_UNUSED(icon);
    Q_UNUSED(title);
    Q_UNUSED(text);

    if (_messageBoxResponseButton == QMessageBox::NoButton) {
        // If no response button is set it means we were not expecting this message box. Response with default
        _missedMessageBoxCount++;
        retButton = defaultButton;
    } else {
        if (_messageBoxResponseButton & buttons) {
            // Everything is correct, use the specified response
            retButton = _messageBoxResponseButton;
        } else {
            // Trying to respond with a button not in the dialog. This is an error. Respond with default
            _badResponseButton = true;
            retButton = defaultButton;
        }
        _messageBoxRespondedTo = true;
    }
    
    // Clear response for next message box
    _messageBoxResponseButton = QMessageBox::NoButton;
    
    return retButton;
}
Don Gagne's avatar
Don Gagne committed
272

273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296
/// @brief Response to a file dialog which returns a single file
QString UnitTest::_fileDialogResponseSingle(enum FileDialogType type)
{
    QString retFile;
    
    if (!_fileDialogResponseSet || _fileDialogExpectedType != type) {
        // If no response is set or the type does not match what we expected it means we were not expecting this file dialog.
        // Respond with no selection.
        _missedFileDialogCount++;
    } else {
        Q_ASSERT(_fileDialogResponse.count() <= 1);
        if (_fileDialogResponse.count() == 1) {
            retFile = _fileDialogResponse[0];
        }
        _fileDialogRespondedTo = true;
    }
    
    // Clear response for next message box
    _fileDialogResponse.clear();
    _fileDialogResponseSet = false;
    
    return retFile;
}

297 298 299 300 301
QString UnitTest::_getExistingDirectory(
    QWidget* parent,
    const QString& caption,
    const QString& dir,
    QFileDialog::Options options)
302 303 304 305 306 307 308 309 310
{
    Q_UNUSED(parent);
    Q_UNUSED(caption);
    Q_UNUSED(dir);
    Q_UNUSED(options);

    return _fileDialogResponseSingle(getExistingDirectory);
}

311 312 313 314 315 316
QString UnitTest::_getOpenFileName(
    QWidget* parent,
    const QString& caption,
    const QString& dir,
    const QString& filter,
    QFileDialog::Options options)
317 318 319 320 321 322 323 324 325 326
{
    Q_UNUSED(parent);
    Q_UNUSED(caption);
    Q_UNUSED(dir);
    Q_UNUSED(filter);
    Q_UNUSED(options);
    
    return _fileDialogResponseSingle(getOpenFileName);
}

327 328 329 330 331 332
QStringList UnitTest::_getOpenFileNames(
    QWidget* parent,
    const QString& caption,
    const QString& dir,
    const QString& filter,
    QFileDialog::Options options)
333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358
{
    Q_UNUSED(parent);
    Q_UNUSED(caption);
    Q_UNUSED(dir);
    Q_UNUSED(filter);
    Q_UNUSED(options);

    QStringList retFiles;
    
    if (!_fileDialogResponseSet || _fileDialogExpectedType != getOpenFileNames) {
        // If no response is set or the type does not match what we expected it means we were not expecting this file dialog.
        // Respond with no selection.
        _missedFileDialogCount++;
        retFiles.clear();
    } else {
        retFiles = _fileDialogResponse;
        _fileDialogRespondedTo = true;
    }
    
    // Clear response for next message box
    _fileDialogResponse.clear();
    _fileDialogResponseSet = false;
    
    return retFiles;
}

359 360 361 362 363
QString UnitTest::_getSaveFileName(
    QWidget* parent,
    const QString& caption,
    const QString& dir,
    const QString& filter,
364 365
    const QString& defaultSuffix,
    QFileDialog::Options options)
366 367 368 369 370 371
{
    Q_UNUSED(parent);
    Q_UNUSED(caption);
    Q_UNUSED(dir);
    Q_UNUSED(filter);
    Q_UNUSED(options);
372

dogmaphobic's avatar
dogmaphobic committed
373
    if(!defaultSuffix.isEmpty()) {
374
        Q_ASSERT(defaultSuffix.startsWith(".") == false);
dogmaphobic's avatar
dogmaphobic committed
375
    }
376

377 378
    return _fileDialogResponseSingle(getSaveFileName);
}
379 380 381 382 383

void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot)
{
    Q_ASSERT(!_mockLink);

384 385 386 387 388 389 390 391 392 393 394 395 396 397
    switch (autopilot) {
    case MAV_AUTOPILOT_PX4:
        _mockLink = MockLink::startPX4MockLink(false);
        break;
    case MAV_AUTOPILOT_ARDUPILOTMEGA:
        _mockLink = MockLink::startAPMArduCopterMockLink(false);
        break;
    case MAV_AUTOPILOT_GENERIC:
        _mockLink = MockLink::startGenericMockLink(false);
        break;
    default:
        qWarning() << "Type not supported";
        break;
    }
398 399 400

    // Wait for the Vehicle to get created
    QSignalSpy spyVehicle(qgcApp()->toolbox()->multiVehicleManager(), SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
Don Gagne's avatar
Don Gagne committed
401
    QCOMPARE(spyVehicle.wait(10000), true);
402
    QVERIFY(qgcApp()->toolbox()->multiVehicleManager()->parameterReadyVehicleAvailable());
403 404
    _vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
    QVERIFY(_vehicle);
405 406 407

    // Wait for plan request to complete
    if (!_vehicle->initialPlanRequestComplete()) {
Don Gagne's avatar
Don Gagne committed
408
        QSignalSpy spyPlan(_vehicle, SIGNAL(initialPlanRequestCompleteChanged(bool)));
409 410
        QCOMPARE(spyPlan.wait(10000), true);
    }
411 412 413 414 415 416 417
}

void UnitTest::_disconnectMockLink(void)
{
    if (_mockLink) {
        QSignalSpy  linkSpy(_linkManager, SIGNAL(linkDeleted(LinkInterface*)));

Don Gagne's avatar
Don Gagne committed
418
        _linkManager->disconnectLink(_mockLink);
419 420 421 422

        // Wait for link to go away
        linkSpy.wait(1000);
        QCOMPARE(linkSpy.count(), 1);
423

424
        _vehicle = nullptr;
425 426 427 428 429 430
    }
}

void UnitTest::_linkDeleted(LinkInterface* link)
{
    if (link == _mockLink) {
431
        _mockLink = nullptr;
432 433 434 435 436
    }
}

void UnitTest::_createMainWindow(void)
{
437 438
    //-- TODO
#if 0
439 440
    _mainWindow = MainWindow::_create();
    Q_CHECK_PTR(_mainWindow);
441
#endif
442 443 444 445
}

void UnitTest::_closeMainWindow(bool cancelExpected)
{
446 447
    //-- TODO
#if 0
448 449 450 451 452 453 454
    if (_mainWindow) {
        QSignalSpy  mainWindowSpy(_mainWindow, SIGNAL(mainWindowClosed()));

        _mainWindow->close();

        mainWindowSpy.wait(2000);
        QCOMPARE(mainWindowSpy.count(), cancelExpected ? 0 : 1);
455 456 457 458

        // This leaves enough time for any dangling Qml components to get cleaned up.
        // This prevents qWarning from bad references in Qml
        QTest::qWait(1000);
459
    }
460 461 462
#else
    Q_UNUSED(cancelExpected);
#endif
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 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531

QString UnitTest::createRandomFile(uint32_t byteCount)
{
    QTemporaryFile tempFile;

    QTime time = QTime::currentTime();
    qsrand((uint)time.msec());

    tempFile.setAutoRemove(false);
    if (tempFile.open()) {
        for (uint32_t bytesWritten=0; bytesWritten<byteCount; bytesWritten++) {
            unsigned char byte = (qrand() * 0xFF) / RAND_MAX;
            tempFile.write((char *)&byte, 1);
        }
        tempFile.close();
        return tempFile.fileName();
    } else {
        qWarning() << "UnitTest::createRandomFile open failed" << tempFile.errorString();
        return QString();
    }
}

bool UnitTest::fileCompare(const QString& file1, const QString& file2)
{
    QFile f1(file1);
    QFile f2(file2);

    if (QFileInfo(file1).size() != QFileInfo(file2).size()) {
        qWarning() << "UnitTest::fileCompare file sizes differ size1:size2" << QFileInfo(file1).size() << QFileInfo(file2).size();
        return false;
    }

    if (!f1.open(QIODevice::ReadOnly)) {
        qWarning() << "UnitTest::fileCompare unable to open file1:" << f1.errorString();
        return false;
    }
    if (!f2.open(QIODevice::ReadOnly)) {
        qWarning() << "UnitTest::fileCompare unable to open file1:" << f1.errorString();
        return false;
    }

    qint64 bytesRemaining = QFileInfo(file1).size();
    qint64 offset = 0;
    while (bytesRemaining) {
        uint8_t b1, b2;

        qint64 bytesRead = f1.read((char*)&b1, 1);
        if (bytesRead != 1) {
            qWarning() << "UnitTest::fileCompare file1 read failed:" << f1.errorString();
            return false;
        }
        bytesRead = f2.read((char*)&b2, 1);
        if (bytesRead != 1) {
            qWarning() << "UnitTest::fileCompare file2 read failed:" << f2.errorString();
            return false;
        }

        if (b1 != b2) {
            qWarning() << "UnitTest::fileCompare mismatch offset:b1:b2" << offset << b1 << b2;
            return false;
        }

        offset++;
        bytesRemaining--;
    }

    return true;
}
532 533 534 535 536 537

bool UnitTest::doubleNaNCompare(double value1, double value2)
{
    if (qIsNaN(value1) && qIsNaN(value2)) {
        return true;
    } else {
538 539 540 541 542
        bool ret = qFuzzyCompare(value1, value2);
        if (!ret) {
            qDebug() << value1 << value2;
        }
        return ret;
543 544
    }
}
545

546
void UnitTest::changeFactValue(Fact* fact,double increment)
547 548 549 550
{
    if (fact->typeIsBool()) {
        fact->setRawValue(!fact->rawValue().toBool());
    } else {
551 552 553 554
        if (increment == 0) {
            increment = 1;
        }
        fact->setRawValue(fact->rawValue().toDouble() + increment);
555 556
    }
}
557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576

void UnitTest::_missionItemsEqual(MissionItem& actual, MissionItem& expected)
{
    QCOMPARE(static_cast<int>(actual.command()),    static_cast<int>(expected.command()));
    QCOMPARE(static_cast<int>(actual.frame()),      static_cast<int>(expected.frame()));
    QCOMPARE(actual.autoContinue(),                 expected.autoContinue());

    QVERIFY(UnitTest::doubleNaNCompare(actual.param1(), expected.param1()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param2(), expected.param2()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param3(), expected.param3()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param4(), expected.param4()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param5(), expected.param5()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param6(), expected.param6()));
    QVERIFY(UnitTest::doubleNaNCompare(actual.param7(), expected.param7()));
}

bool UnitTest::fuzzyCompareLatLon(const QGeoCoordinate& coord1, const QGeoCoordinate& coord2)
{
    return coord1.distanceTo(coord2) < 1.0;
}