SurveyComplexItemTest.cc 7.37 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
9

10
#include "SurveyComplexItemTest.h"
Don Gagne's avatar
Don Gagne committed
11
#include "QGCApplication.h"
12

13
SurveyComplexItemTest::SurveyComplexItemTest(void)
Don Gagne's avatar
Don Gagne committed
14 15
    : _offlineVehicle(NULL)
{
16
    _polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) <<
Don Gagne's avatar
Don Gagne committed
17
                   QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124);
18 19
}

20
void SurveyComplexItemTest::init(void)
21
{
Don Gagne's avatar
Don Gagne committed
22 23
    UnitTest::init();

24 25 26 27 28 29
    _rgSurveySignals[surveyVisualTransectPointsChangedIndex] =    SIGNAL(visualTransectPointsChanged());
    _rgSurveySignals[surveyCameraShotsChangedIndex] =             SIGNAL(cameraShotsChanged());
    _rgSurveySignals[surveyCoveredAreaChangedIndex] =             SIGNAL(coveredAreaChanged());
    _rgSurveySignals[surveyTimeBetweenShotsChangedIndex] =        SIGNAL(timeBetweenShotsChanged());
    _rgSurveySignals[surveyRefly90DegreesChangedIndex] =          SIGNAL(refly90DegreesChanged(bool));
    _rgSurveySignals[surveyDirtyChangedIndex] =                   SIGNAL(dirtyChanged(bool));
Don Gagne's avatar
Don Gagne committed
30 31

    _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
32
    _surveyItem = new SurveyComplexItem(_offlineVehicle, this);
33
    _surveyItem->turnAroundDistance()->setRawValue(0);  // Unit test written for no turnaround distance
DonLakeFlyer's avatar
DonLakeFlyer committed
34
    _surveyItem->setDirty(false);
35
    _mapPolygon = _surveyItem->surveyAreaPolygon();
36 37 38 39 40 41 42

    // It's important to check that the right signals are emitted at the right time since that drives ui change.
    // It's also important to check that things are not being over-signalled when they should not be, since that can lead
    // to incorrect ui or perf impact of uneeded signals propogating ui change.

    _multiSpy = new MultiSignalSpy();
    Q_CHECK_PTR(_multiSpy);
Don Gagne's avatar
Don Gagne committed
43
    QCOMPARE(_multiSpy->init(_surveyItem, _rgSurveySignals, _cSurveySignals), true);
44 45
}

46
void SurveyComplexItemTest::cleanup(void)
47
{
48
    delete _surveyItem;
Don Gagne's avatar
Don Gagne committed
49
    delete _offlineVehicle;
50 51 52
    delete _multiSpy;
}

53
void SurveyComplexItemTest::_testDirty(void)
54
{
55 56 57
    QVERIFY(!_surveyItem->dirty());
    _surveyItem->setDirty(false);
    QVERIFY(!_surveyItem->dirty());
58
    QVERIFY(_multiSpy->checkNoSignals());
Don Gagne's avatar
Don Gagne committed
59

60 61
    _surveyItem->setDirty(true);
    QVERIFY(_surveyItem->dirty());
62 63
    QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
    QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
64
    _multiSpy->clearAllSignals();
Don Gagne's avatar
Don Gagne committed
65

66 67
    _surveyItem->setDirty(false);
    QVERIFY(!_surveyItem->dirty());
68 69
    QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
    QVERIFY(!_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
Don Gagne's avatar
Don Gagne committed
70 71 72 73
    _multiSpy->clearAllSignals();

    // These facts should set dirty when changed
    QList<Fact*> rgFacts;
74
    rgFacts << _surveyItem->gridAngle() << _surveyItem->gridEntryLocation();
Don Gagne's avatar
Don Gagne committed
75 76 77 78 79 80 81 82
    foreach(Fact* fact, rgFacts) {
        qDebug() << fact->name();
        QVERIFY(!_surveyItem->dirty());
        if (fact->typeIsBool()) {
            fact->setRawValue(!fact->rawValue().toBool());
        } else {
            fact->setRawValue(fact->rawValue().toDouble() + 1);
        }
83 84
        QVERIFY(_multiSpy->checkSignalByMask(surveyDirtyChangedMask));
        QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
Don Gagne's avatar
Don Gagne committed
85 86 87 88
        _surveyItem->setDirty(false);
        _multiSpy->clearAllSignals();
    }
    rgFacts.clear();
89
}
90 91

// Clamp expected grid angle from 0<->180. We don't care about opposite angles like 90/270
92
double SurveyComplexItemTest::_clampGridAngle180(double gridAngle)
93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109
{
    if (gridAngle >= 0.0) {
        if (gridAngle == 360.0) {
            gridAngle = 0.0;
        } else if (gridAngle >= 180.0) {
            gridAngle -= 180.0;
        }
    } else {
        if (gridAngle < -180.0) {
            gridAngle += 360.0;
        } else {
            gridAngle += 180.0;
        }
    }
    return gridAngle;
}

110
void SurveyComplexItemTest::_setPolygon(void)
111 112 113
{
    for (int i=0; i<_polyPoints.count(); i++) {
        QGeoCoordinate& vertex = _polyPoints[i];
114
        _mapPolygon->appendVertex(vertex);
115
    }
116 117
}

118
void SurveyComplexItemTest::_testGridAngle(void)
119 120
{
    _setPolygon();
121 122 123 124

    for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
        _surveyItem->gridAngle()->setRawValue(gridAngle);

125
        QVariantList gridPoints = _surveyItem->visualTransectPoints();
126 127 128 129 130 131 132 133
        QGeoCoordinate firstTransectEntry = gridPoints[0].value<QGeoCoordinate>();
        QGeoCoordinate firstTransectExit = gridPoints[1].value<QGeoCoordinate>();
        double azimuth = firstTransectEntry.azimuthTo(firstTransectExit);
        //qDebug() << gridAngle << azimuth << _clampGridAngle180(gridAngle) << _clampGridAngle180(azimuth);
        QCOMPARE((int)_clampGridAngle180(gridAngle), (int)_clampGridAngle180(azimuth));
    }
}

134
void SurveyComplexItemTest::_testEntryLocation(void)
135
{
136
    _setPolygon();
137 138 139 140 141 142

    for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
        _surveyItem->gridAngle()->setRawValue(gridAngle);

        QList<QGeoCoordinate> rgSeenEntryCoords;
        QList<int> rgEntryLocation;
143 144 145 146
        rgEntryLocation << SurveyComplexItem::EntryLocationTopLeft
                        << SurveyComplexItem::EntryLocationTopRight
                        << SurveyComplexItem::EntryLocationBottomLeft
                        << SurveyComplexItem::EntryLocationBottomRight;
147 148 149 150 151 152 153 154 155 156 157 158

        // Validate that each entry location is unique
        for (int i=0; i<rgEntryLocation.count(); i++) {
            int entryLocation = rgEntryLocation[i];

            _surveyItem->gridEntryLocation()->setRawValue(entryLocation);
            QVERIFY(!rgSeenEntryCoords.contains(_surveyItem->coordinate()));
            rgSeenEntryCoords << _surveyItem->coordinate();
        }
        rgSeenEntryCoords.clear();
    }
}
159 160


161
void SurveyComplexItemTest::_testItemCount(void)
162 163 164 165 166 167
{
    QList<MissionItem*> items;

    _setPolygon();

    _surveyItem->hoverAndCapture()->setRawValue(false);
168 169
    _surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
    _surveyItem->refly90Degrees()->setRawValue(false);
170
    _surveyItem->appendMissionItems(items, this);
171
    QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
172 173 174
    items.clear();

    _surveyItem->hoverAndCapture()->setRawValue(false);
175 176
    _surveyItem->cameraTriggerInTurnAround()->setRawValue(true);
    _surveyItem->refly90Degrees()->setRawValue(false);
177
    _surveyItem->appendMissionItems(items, this);
178
    QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
179 180 181
    items.clear();

    _surveyItem->hoverAndCapture()->setRawValue(true);
182 183
    _surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
    _surveyItem->refly90Degrees()->setRawValue(false);
184
    _surveyItem->appendMissionItems(items, this);
185
    QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
186 187 188
    items.clear();

    _surveyItem->hoverAndCapture()->setRawValue(true);
189 190
    _surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
    _surveyItem->refly90Degrees()->setRawValue(true);
191
    _surveyItem->appendMissionItems(items, this);
192
    QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
193 194
    items.clear();
}