SurveyComplexItemTest.cc 14.3 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
 *
 * 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
#include "JsonHelper.h"
13

14
SurveyComplexItemTest::SurveyComplexItemTest(void)
Don Gagne's avatar
Don Gagne committed
15
{
16 17 18 19 20 21
    // We use a 100m by 100m square test polygon
    const double edgeDistance = 100;
    _polyVertices.append(QGeoCoordinate(47.633550640000003, -122.08982199));
    _polyVertices.append(_polyVertices[0].atDistanceAndAzimuth(edgeDistance, 90));
    _polyVertices.append(_polyVertices[1].atDistanceAndAzimuth(edgeDistance, 180));
    _polyVertices.append(_polyVertices[2].atDistanceAndAzimuth(edgeDistance, -90.0));
22 23
}

24
void SurveyComplexItemTest::init(void)
25
{
26
    TransectStyleComplexItemTestBase::init();
Don Gagne's avatar
Don Gagne committed
27

28 29 30 31 32 33
    _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
34

35
    _surveyItem = new SurveyComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */, this /* parent */);
36
    _mapPolygon = _surveyItem->surveyAreaPolygon();
37 38 39 40 41 42 43 44 45 46 47 48 49 50 51
    _mapPolygon->appendVertices(_polyVertices);

    QVERIFY(_surveyItem->cameraCalc()->isManualCamera());

    // Set grid spacing to match expected transect count
    double polyWidthDistance = _polyVertices[0].distanceTo(_polyVertices[1]);
    double polyHeightDistance = _polyVertices[0].distanceTo(_polyVertices[3]);
    _surveyItem->cameraCalc()->adjustedFootprintSide()->setRawValue((polyWidthDistance * 0.5) - 1.0);
    _surveyItem->cameraCalc()->adjustedFootprintFrontal()->setRawValue(polyHeightDistance * 0.25);

    _surveyItem->gridAngle()->setRawValue(0);
    int expectedTransectCount = _expectedTransectCount;
    QCOMPARE(_surveyItem->_transectCount(), expectedTransectCount);

    _surveyItem->setDirty(false);
52 53 54 55 56 57 58

    // 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
59
    QCOMPARE(_multiSpy->init(_surveyItem, _rgSurveySignals, _cSurveySignals), true);
60 61
}

62
void SurveyComplexItemTest::cleanup(void)
63
{
64
    delete _surveyItem;
65
    delete _multiSpy;
66 67

    TransectStyleComplexItemTestBase::cleanup();
68 69
}

70
void SurveyComplexItemTest::_testDirty(void)
71
{
72 73 74
    QVERIFY(!_surveyItem->dirty());
    _surveyItem->setDirty(false);
    QVERIFY(!_surveyItem->dirty());
75
    QVERIFY(_multiSpy->checkNoSignals());
Don Gagne's avatar
Don Gagne committed
76

77 78
    _surveyItem->setDirty(true);
    QVERIFY(_surveyItem->dirty());
79 80
    QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
    QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
81
    _multiSpy->clearAllSignals();
Don Gagne's avatar
Don Gagne committed
82

83 84
    _surveyItem->setDirty(false);
    QVERIFY(!_surveyItem->dirty());
85
    QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
Don Gagne's avatar
Don Gagne committed
86 87 88 89
    _multiSpy->clearAllSignals();

    // These facts should set dirty when changed
    QList<Fact*> rgFacts;
90
    rgFacts << _surveyItem->gridAngle() << _surveyItem->flyAlternateTransects();
91
    for(Fact* fact: rgFacts) {
Don Gagne's avatar
Don Gagne committed
92 93 94 95 96 97 98
        qDebug() << fact->name();
        QVERIFY(!_surveyItem->dirty());
        if (fact->typeIsBool()) {
            fact->setRawValue(!fact->rawValue().toBool());
        } else {
            fact->setRawValue(fact->rawValue().toDouble() + 1);
        }
99 100
        QVERIFY(_multiSpy->checkSignalByMask(surveyDirtyChangedMask));
        QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
Don Gagne's avatar
Don Gagne committed
101 102 103 104
        _surveyItem->setDirty(false);
        _multiSpy->clearAllSignals();
    }
    rgFacts.clear();
105
}
106 107

// Clamp expected grid angle from 0<->180. We don't care about opposite angles like 90/270
108
double SurveyComplexItemTest::_clampGridAngle180(double gridAngle)
109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125
{
    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;
}

126
void SurveyComplexItemTest::_testGridAngle(void)
127
{
128 129 130
    for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
        _surveyItem->gridAngle()->setRawValue(gridAngle);

131
        QVariantList gridPoints = _surveyItem->visualTransectPoints();
132 133 134 135
        QGeoCoordinate firstTransectEntry = gridPoints[0].value<QGeoCoordinate>();
        QGeoCoordinate firstTransectExit = gridPoints[1].value<QGeoCoordinate>();
        double azimuth = firstTransectEntry.azimuthTo(firstTransectExit);
        //qDebug() << gridAngle << azimuth << _clampGridAngle180(gridAngle) << _clampGridAngle180(azimuth);
136 137 138
        int clampGridAngle = qRound(_clampGridAngle180(gridAngle));
        int clampAzimuth = qRound(_clampGridAngle180(azimuth));
        QCOMPARE(clampGridAngle, clampAzimuth);
139 140 141
    }
}

142
void SurveyComplexItemTest::_testEntryLocation(void)
143 144 145 146 147
{
    for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
        _surveyItem->gridAngle()->setRawValue(gridAngle);

        // Validate that each entry location is unique
DonLakeFlyer's avatar
DonLakeFlyer committed
148 149 150
        QList<QGeoCoordinate> rgSeenEntryCoords;
        for (int rotateCount=0; rotateCount<3; rotateCount++) {
            _surveyItem->rotateEntryPoint();
151 152 153
            QVERIFY(!rgSeenEntryCoords.contains(_surveyItem->coordinate()));
            rgSeenEntryCoords << _surveyItem->coordinate();
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
154 155

        _surveyItem->rotateEntryPoint();    // Rotate back for first entry point
156 157 158
        rgSeenEntryCoords.clear();
    }
}
159

160
void SurveyComplexItemTest::_testItemCount(void)
161
{
162 163 164 165 166 167
    typedef struct {
        bool        hoverAndCapture;
        bool        triggerInTurnAround;
        bool        refly90;
        bool        hasTurnaround;
    } TestCase_t;
168

169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184
    QList<TestCase_t> rgTestCases;

    for (int i=0; i<2; i++) {
        for (int j=0; i<2; i++) {
            for (int k=0; i<2; i++) {
                for (int l=0; i<2; i++) {
                    TestCase_t testCase;
                    testCase.hoverAndCapture =      i;
                    testCase.triggerInTurnAround =  j;
                    testCase.refly90 =              k;
                    testCase.hasTurnaround =        l;
                    rgTestCases.append(testCase);
                }
            }
        }
    }
185

186 187 188 189 190 191 192 193 194 195 196
    QList<MissionItem*> items;
    for (const TestCase_t& testCase : rgTestCases) {
        qDebug() << "hoverAndCapture:triggerInTurnAround:refly90:hasTuraround" << testCase.hoverAndCapture << testCase.triggerInTurnAround << testCase.refly90 << testCase.hasTurnaround;
        _surveyItem->hoverAndCapture()->setRawValue(testCase.hoverAndCapture);
        _surveyItem->cameraTriggerInTurnAround()->setRawValue(testCase.triggerInTurnAround);
        _surveyItem->refly90Degrees()->setRawValue(testCase.refly90);
        _surveyItem->turnAroundDistance()->setRawValue(testCase.hasTurnaround ? 50 : 0);
        _surveyItem->appendMissionItems(items, this);
        QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
        items.clear();
    }
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 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242

QList<MAV_CMD> SurveyComplexItemTest::_createExpectedCommands(bool hasTurnaround, bool useConditionGate)
{
    static const QList<MAV_CMD> singleFullTransect = {
        MAV_CMD_NAV_WAYPOINT,           // Turnaround
        MAV_CMD_CONDITION_GATE,         // Survey area entry edge
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
        MAV_CMD_CONDITION_GATE,         // Survey area exit edge
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
        MAV_CMD_NAV_WAYPOINT,
    };

    QList<MAV_CMD> singleTransect = singleFullTransect;
    QList<MAV_CMD> expectedCommands;

    if (!useConditionGate) {
        for (MAV_CMD& cmd : singleTransect) {
            cmd = cmd == MAV_CMD_CONDITION_GATE ? MAV_CMD_NAV_WAYPOINT : cmd;
        }
    }

    if (!hasTurnaround) {
        singleTransect.takeFirst();
        singleTransect.takeLast();
    }
    
    for (int i=0; i<_expectedTransectCount; i++) {
        expectedCommands.append(singleTransect);
    }

    return expectedCommands;
}

void SurveyComplexItemTest::_testItemGenerationWorker(bool imagesInTurnaround, bool hasTurnaround, bool useConditionGate, const QList<MAV_CMD>& expectedCommands)
{
    qDebug() << QStringLiteral("_testItemGenerationWorker imagesInTuraround:%1 turnaround:%2 gate:%3").arg(imagesInTurnaround).arg(hasTurnaround).arg(useConditionGate);

    _surveyItem->turnAroundDistance()->setRawValue(hasTurnaround ? 50 : 0);
    _surveyItem->cameraTriggerInTurnAround()->setRawValue(imagesInTurnaround);
    _planViewSettings->useConditionGate()->setRawValue(useConditionGate);

    QList<MissionItem*> items;
    _surveyItem->appendMissionItems(items, this);
#if 0
    // Handy for debugging failures
243
    _printItemCommands(items);
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 272 273 274 275 276 277 278
#endif
    QCOMPARE(items.count(), expectedCommands.count());
    for (int i=0; i<expectedCommands.count(); i++) {
        int actualCommand = items[i]->command();
        int expectedCommand = expectedCommands[i];
#if 0
        // Handy for debugging failures
        qDebug() << "Index" << i;
#endif
        QCOMPARE(actualCommand, expectedCommand);
    }
}

void SurveyComplexItemTest::_testItemGeneration(void)
{
    // Test all the combinations of: cameraTriggerInTurnAround: false, hasTurnAround: *, useConditionGate: *

    typedef struct {
        bool        hasTurnaround;
        bool        useConditionGate;
    } TestCase_t;

    static const TestCase_t rgTestCases[] = {
        { false,    false },
        { false,    true },
        { true,     false },
        { true,     true },
    };

    for (const TestCase_t& testCase : rgTestCases) {
        _testItemGenerationWorker(false /* imagesInTurnaround */, testCase.hasTurnaround, testCase.useConditionGate, _createExpectedCommands(testCase.hasTurnaround, testCase.useConditionGate));
    }

    // Test cameraTriggerInTurnAround = true cases

279
    QList<MAV_CMD> imagesInTurnaroundWithTurnaroundDistanceCommands = {
280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295
        // Transect 1
        MAV_CMD_CONDITION_GATE,         // First turaround
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
        MAV_CMD_CONDITION_GATE,         // Survey entry
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,  // Survey entry also has trigger start
        MAV_CMD_NAV_WAYPOINT,           // Survey exit
        MAV_CMD_NAV_WAYPOINT,           // Turnaround
        // Transect 2
        MAV_CMD_NAV_WAYPOINT,           // Turnaround
        MAV_CMD_CONDITION_GATE,         // Survey entry
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,  // Survey entry also has trigger start
        MAV_CMD_NAV_WAYPOINT,           // Survey exit
        MAV_CMD_CONDITION_GATE,         // Final turnaround
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
    };

296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316
    _testItemGenerationWorker(true /* imagesInTurnaround */, true /* hasTurnaround */, true /* useConditionGate */, imagesInTurnaroundWithTurnaroundDistanceCommands);

    // Switch to non CONDITION_GATE usage
    for (MAV_CMD& cmd : imagesInTurnaroundWithTurnaroundDistanceCommands) {
        cmd = cmd == MAV_CMD_CONDITION_GATE ? MAV_CMD_NAV_WAYPOINT : cmd;
    }
    _testItemGenerationWorker(true /* imagesInTurnaround */, true /* hasTurnaround */, false /* useConditionGate */, imagesInTurnaroundWithTurnaroundDistanceCommands);

    QList<MAV_CMD> imagesInTurnaroundWithoutTurnaroundDistanceCommands = {
        // Transect 1
        MAV_CMD_CONDITION_GATE,         // Survey entry
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,  // Camera trigger start for entire survey
        MAV_CMD_NAV_WAYPOINT,           // Survey exit
        // Transect 2
        MAV_CMD_CONDITION_GATE,         // Survey entry
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,  // Survey entry also has trigger start
        MAV_CMD_CONDITION_GATE,         // Survey exit
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,  // Camera trigger stop for entire survey
    };

    _testItemGenerationWorker(true /* imagesInTurnaround */, false /* hasTurnaround */, true /* useConditionGate */, imagesInTurnaroundWithoutTurnaroundDistanceCommands);
317 318

    // Switch to non CONDITION_GATE usage
319
    for (MAV_CMD& cmd : imagesInTurnaroundWithoutTurnaroundDistanceCommands) {
320 321
        cmd = cmd == MAV_CMD_CONDITION_GATE ? MAV_CMD_NAV_WAYPOINT : cmd;
    }
322
    _testItemGenerationWorker(true /* imagesInTurnaround */, false /* hasTurnaround */, false /* useConditionGate */, imagesInTurnaroundWithoutTurnaroundDistanceCommands);
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
}

void SurveyComplexItemTest::_testHoverCaptureItemGeneration(void)
{
    static const QList<MAV_CMD> singleFullTransect = {
        MAV_CMD_NAV_WAYPOINT,           // Turnaround
        MAV_CMD_NAV_WAYPOINT,           // Survey area entry edge
        MAV_CMD_IMAGE_START_CAPTURE,
        MAV_CMD_NAV_WAYPOINT,           // Interior trigger
        MAV_CMD_IMAGE_START_CAPTURE,
        MAV_CMD_NAV_WAYPOINT,           // Interior trigger
        MAV_CMD_IMAGE_START_CAPTURE,
        MAV_CMD_NAV_WAYPOINT,           // Survey area exit edge
        MAV_CMD_IMAGE_START_CAPTURE,
        MAV_CMD_NAV_WAYPOINT,           // Turnaround
    };

    QList<MAV_CMD> expectedCommands;
    for (int i=0; i<_expectedTransectCount; i++) {
        expectedCommands.append(singleFullTransect);
    }

    // Set trigger distance to generates two interior capture points
    double polyHeightDistance = _polyVertices[0].distanceTo(_polyVertices[3]);
    double triggerDistance = (polyHeightDistance / 3.0) + 1.0;
    _surveyItem->cameraCalc()->adjustedFootprintFrontal()->setRawValue(triggerDistance);

    _surveyItem->hoverAndCapture()->setRawValue(true);
    _testItemGenerationWorker(false /* imagesInTurnaround */, true /* hasTurnaround */, true /* useConditionGate */, expectedCommands);
    _testItemGenerationWorker(false /* imagesInTurnaround */, true /* hasTurnaround */, false /* useConditionGate */, expectedCommands);
}