FWLandingPatternTest.cc 9.64 KB
Newer Older
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 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "FWLandingPatternTest.h"
#include "QGCApplication.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
#include "CameraSectionTest.h"

FWLandingPatternTest::FWLandingPatternTest(void)
    : _offlineVehicle           (Q_NULLPTR)
    , _fwItem                   (Q_NULLPTR)
    , _multiSpy                 (Q_NULLPTR)
    , _validStopVideoItem       (Q_NULLPTR)
    , _validStopDistanceItem    (Q_NULLPTR)
    , _validStopTimeItem        (Q_NULLPTR)
{
    
}

void FWLandingPatternTest::init(void)
{
    UnitTest::init();

    rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));

    _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
    _fwItem = new FixedWingLandingComplexItem(_offlineVehicle, false /* flyView */, this);
    _multiSpy = new MultiSignalSpy();
    QCOMPARE(_multiSpy->init(_fwItem, rgSignals, cSignals), true);

    // Start in a clean state
    QVERIFY(!_fwItem->dirty());
    _fwItem->setLandingCoordinate(QGeoCoordinate(47, -122));
    _fwItem->setDirty(false);
    QVERIFY(!_fwItem->dirty());
    _multiSpy->clearAllSignals();

    _validStopVideoItem =       CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
    _validStopDistanceItem =    CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
    _validStopTimeItem =        CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
}

void FWLandingPatternTest::cleanup(void)
{
    delete _fwItem;
    delete _offlineVehicle;
    delete _multiSpy;
    delete _validStopVideoItem;
    delete _validStopDistanceItem;
    delete _validStopTimeItem;
    UnitTest::cleanup();
}


void FWLandingPatternTest::_testDefaults(void)
{
    QCOMPARE(_fwItem->stopTakingPhotos()->rawValue().toBool(), true);
    QCOMPARE(_fwItem->stopTakingVideo()->rawValue().toBool(), true);
}

void FWLandingPatternTest::_testItemCount(void)
{
    QList<MissionItem*> items;

    _fwItem->stopTakingPhotos()->setRawValue(true);
    _fwItem->stopTakingVideo()->setRawValue(true);
    _fwItem->appendMissionItems(items, this);
    QCOMPARE(items.count(), 3 + CameraSection::stopTakingPhotosCommandCount() + CameraSection::stopTakingVideoCommandCount());
    QCOMPARE(items.count() - 1, _fwItem->lastSequenceNumber());
    items.clear();

    _fwItem->stopTakingPhotos()->setRawValue(false);
    _fwItem->stopTakingVideo()->setRawValue(false);
    _fwItem->appendMissionItems(items, this);
    QCOMPARE(items.count(), 3);
    QCOMPARE(items.count() - 1, _fwItem->lastSequenceNumber());
    items.clear();
}

void FWLandingPatternTest::_testAppendSectionItems(void)
{
    QList<MissionItem*> rgMissionItems;

    // Create the set of appended mission items
    _fwItem->stopTakingPhotos()->setRawValue(true);
    _fwItem->stopTakingVideo()->setRawValue(true);
    _fwItem->appendMissionItems(rgMissionItems, this);

    // Convert to visual items
    QmlObjectListModel* simpleItems = new QmlObjectListModel(this);

    for (MissionItem* item: rgMissionItems) {
        SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
        simpleItem->missionItem() = *item;
        simpleItems->append(simpleItem);
    }

    // Scan the items back in to verify the same values come back
    // Note that the compares does the best it can with doubles going to floats and back causing inaccuracies beyond a fuzzy compare.
    QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _offlineVehicle));
    QCOMPARE(simpleItems->count(), 1);
    _validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));

    // Reset
    simpleItems->deleteLater();
    rgMissionItems.clear();

    // Check for no stop camera actions
    _fwItem->stopTakingPhotos()->setRawValue(false);
    _fwItem->stopTakingVideo()->setRawValue(false);
    _fwItem->appendMissionItems(rgMissionItems, this);
    simpleItems = new QmlObjectListModel(this);
    for (MissionItem* item: rgMissionItems) {
        SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
        simpleItem->missionItem() = *item;
        simpleItems->append(simpleItem);
    }
    QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _offlineVehicle));
    QCOMPARE(simpleItems->count(), 1);
    _validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));

    // Reset
    simpleItems->deleteLater();
    rgMissionItems.clear();
}

void FWLandingPatternTest::_testDirty(void)
{
    _fwItem->setDirty(true);
    QVERIFY(_fwItem->dirty());
    QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
    QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
    _fwItem->setDirty(false);
    _multiSpy->clearAllSignals();

    // These facts should set dirty when changed
    QList<Fact*> rgFacts;
    rgFacts << _fwItem->loiterAltitude()
            << _fwItem->landingHeading()
            << _fwItem->loiterRadius()
            << _fwItem->landingAltitude()
            << _fwItem->landingDistance()
            << _fwItem->glideSlope()
            << _fwItem->stopTakingPhotos()
152 153
            << _fwItem->stopTakingVideo()
            << _fwItem->valueSetIsDistance();
154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170
    for(Fact* fact: rgFacts) {
        qDebug() << fact->name();
        QVERIFY(!_fwItem->dirty());
        if (fact->typeIsBool()) {
            fact->setRawValue(!fact->rawValue().toBool());
        } else {
            fact->setRawValue(fact->rawValue().toDouble() + 1);
        }
        QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
        QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
        _fwItem->setDirty(false);
        _multiSpy->clearAllSignals();
    }
    rgFacts.clear();

    // These bool properties should set dirty when changed
    QList<const char*> rgBoolNames;
171
    rgBoolNames << "loiterClockwise"
172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225
                << "altitudesAreRelative";
    const QMetaObject* metaObject = _fwItem->metaObject();
    for(const char* boolName: rgBoolNames) {
        qDebug() << boolName;
        QVERIFY(!_fwItem->dirty());
        QMetaProperty boolProp = metaObject->property(metaObject->indexOfProperty(boolName));
        QVERIFY(boolProp.write(_fwItem, !boolProp.read(_fwItem).toBool()));
        QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
        QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
        _fwItem->setDirty(false);
        _multiSpy->clearAllSignals();
    }
    rgFacts.clear();

    // These coordinates should set dirty when changed
    QVERIFY(!_fwItem->dirty());
    _fwItem->setLoiterCoordinate(_fwItem->loiterCoordinate().atDistanceAndAzimuth(1, 0));
    QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
    QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
    _fwItem->setDirty(false);
    _multiSpy->clearAllSignals();
    QVERIFY(!_fwItem->dirty());
    _fwItem->setLoiterCoordinate(_fwItem->landingCoordinate().atDistanceAndAzimuth(1, 0));
    QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
    QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
    _fwItem->setDirty(false);
    _multiSpy->clearAllSignals();
}

void FWLandingPatternTest::_testSaveLoad(void)
{
    QJsonArray  items;
    _fwItem->save(items);

    QString errorString;
    FixedWingLandingComplexItem* newItem = new FixedWingLandingComplexItem(_offlineVehicle, false /* flyView */, this /* parent */);
    bool success =newItem->load(items[0].toObject(), 10, errorString);
    if (!success) {
        qDebug() << errorString;
    }
    QVERIFY(success);
    QVERIFY(errorString.isEmpty());
    _validateItem(newItem);
    newItem->deleteLater();
}

void FWLandingPatternTest::_validateItem(FixedWingLandingComplexItem* newItem)
{
    QVERIFY(newItem);

    QVERIFY(fuzzyCompareLatLon(newItem->loiterCoordinate(),         _fwItem->loiterCoordinate()));
    QVERIFY(fuzzyCompareLatLon(newItem->loiterTangentCoordinate(),  _fwItem->loiterTangentCoordinate()));
    QVERIFY(fuzzyCompareLatLon(newItem->landingCoordinate(),        _fwItem->landingCoordinate()));

226 227 228 229 230 231 232 233 234 235 236 237
    QCOMPARE(newItem->stopTakingPhotos()->rawValue().toBool(),      _fwItem->stopTakingPhotos()->rawValue().toBool());
    QCOMPARE(newItem->stopTakingVideo()->rawValue().toBool(),       _fwItem->stopTakingVideo()->rawValue().toBool());
    QCOMPARE(newItem->loiterAltitude()->rawValue().toInt(),         _fwItem->loiterAltitude()->rawValue().toInt());
    QCOMPARE(newItem->loiterRadius()->rawValue().toInt(),           _fwItem->loiterRadius()->rawValue().toInt());
    QCOMPARE(newItem->landingAltitude()->rawValue().toInt(),        _fwItem->landingAltitude()->rawValue().toInt());
    QCOMPARE(newItem->landingHeading()->rawValue().toInt(),         _fwItem->landingHeading()->rawValue().toInt());
    QCOMPARE(newItem->landingDistance()->rawValue().toInt(),        _fwItem->landingDistance()->rawValue().toInt());
    QCOMPARE(newItem->glideSlope()->rawValue().toInt(),             _fwItem->glideSlope()->rawValue().toInt());
    QCOMPARE(newItem->valueSetIsDistance()->rawValue().toBool(),    _fwItem->valueSetIsDistance()->rawValue().toBool());
    QCOMPARE(newItem->_loiterClockwise,                             _fwItem->_loiterClockwise);
    QCOMPARE(newItem->_altitudesAreRelative,                        _fwItem->_altitudesAreRelative);
    QCOMPARE(newItem->_landingCoordSet,                             _fwItem->_landingCoordSet);
238
}