SimpleMissionItemTest.cc 15.2 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.
 *
 ****************************************************************************/

10 11

#include "SimpleMissionItemTest.h"
12
#include "QGCApplication.h"
13
#include "QGroundControlQmlGlobal.h"
14
#include "SettingsManager.h"
15
#include "PlanMasterController.h"
16 17 18

const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
    { MAV_CMD_NAV_WAYPOINT,     MAV_FRAME_GLOBAL_RELATIVE_ALT },
19
    { MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL },
20
    { MAV_CMD_NAV_LOITER_TURNS, MAV_FRAME_GLOBAL_RELATIVE_ALT },
21
    { MAV_CMD_NAV_LOITER_TIME,  MAV_FRAME_GLOBAL },
22
    { MAV_CMD_NAV_LAND,         MAV_FRAME_GLOBAL_RELATIVE_ALT },
23
    { MAV_CMD_NAV_TAKEOFF,      MAV_FRAME_GLOBAL },
24 25 26 27
    { MAV_CMD_DO_JUMP,          MAV_FRAME_MISSION },
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesWaypoint[] = {
Don Gagne's avatar
Don Gagne committed
28
    { "Hold",       10.1234567 },
29 30 31
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterUnlim[] = {
Don Gagne's avatar
Don Gagne committed
32
    { "Radius",     30.1234567 },
33 34 35
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTurns[] = {
Don Gagne's avatar
Don Gagne committed
36 37
    { "Radius",     30.1234567 },
    { "Turns",      10.1234567 },
38 39 40
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTime[] = {
Don Gagne's avatar
Don Gagne committed
41 42
    { "Radius",     30.1234567 },
    { "Hold",       10.1234567 },
43 44 45
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesTakeoff[] = {
Don Gagne's avatar
Don Gagne committed
46
    { "Pitch",      10.1234567 },
47 48 49
};

const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJump[] = {
Don Gagne's avatar
Don Gagne committed
50 51
    { "Item #",     10.1234567 },
    { "Repeat",     20.1234567 },
52 53 54
};

const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = {
55
    // Text field facts count                                                                                                   Fact Values                                         Altitude    Altitude Mode
56 57 58 59 60 61 62
    { sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]),             SimpleMissionItemTest::_rgFactValuesWaypoint,       70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
    { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]),       SimpleMissionItemTest::_rgFactValuesLoiterUnlim,    70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
    { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]),       SimpleMissionItemTest::_rgFactValuesLoiterTurns,    70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
    { sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]),         SimpleMissionItemTest::_rgFactValuesLoiterTime,     70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
    { 0,                                                                                                                        nullptr,                                               70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
    { sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]),               SimpleMissionItemTest::_rgFactValuesTakeoff,        70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
    { sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]),                 SimpleMissionItemTest::_rgFactValuesDoJump,         qQNaN(),    QGroundControlQmlGlobal::AltitudeModeRelative },
63 64 65
};

SimpleMissionItemTest::SimpleMissionItemTest(void)
66
    : _simpleItem(nullptr)
67 68 69 70
{
    
}

Don Gagne's avatar
Don Gagne committed
71 72
void SimpleMissionItemTest::init(void)
{
73 74
    VisualMissionItemTest::init();

75
    rgSimpleItemSignals[commandChangedIndex] =                          SIGNAL(commandChanged(int));
76
    rgSimpleItemSignals[altitudeModeChangedIndex] =                     SIGNAL(altitudeModeChanged());
77 78 79
    rgSimpleItemSignals[friendlyEditAllowedChangedIndex] =              SIGNAL(friendlyEditAllowedChanged(bool));
    rgSimpleItemSignals[headingDegreesChangedIndex] =                   SIGNAL(headingDegreesChanged(double));
    rgSimpleItemSignals[rawEditChangedIndex] =                          SIGNAL(rawEditChanged(bool));
80 81
    rgSimpleItemSignals[cameraSectionChangedIndex] =                    SIGNAL(cameraSectionChanged(QObject*));
    rgSimpleItemSignals[speedSectionChangedIndex] =                     SIGNAL(speedSectionChanged(QObject*));
82
    rgSimpleItemSignals[coordinateHasRelativeAltitudeChangedIndex] =    SIGNAL(coordinateHasRelativeAltitudeChanged(bool));
83 84 85 86 87 88 89 90 91 92 93 94 95

    MissionItem missionItem(1,              // sequence number
                            MAV_CMD_NAV_WAYPOINT,
                            MAV_FRAME_GLOBAL_RELATIVE_ALT,
                            10.1234567,     // param 1-7
                            20.1234567,
                            30.1234567,
                            40.1234567,
                            50.1234567,
                            60.1234567,
                            70.1234567,
                            true,           // autoContinue
                            false);         // isCurrentItem
96
    _simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
97 98 99 100

    // It's important top 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.
Don Gagne's avatar
Don Gagne committed
101

102 103
    _spySimpleItem = new MultiSignalSpy();
    QCOMPARE(_spySimpleItem->init(_simpleItem, rgSimpleItemSignals, cSimpleItemSignals), true);
104
    VisualMissionItemTest::_createSpy(_simpleItem, &_spyVisualItem);
Don Gagne's avatar
Don Gagne committed
105 106 107 108
}

void SimpleMissionItemTest::cleanup(void)
{
109 110
    delete _simpleItem;
    VisualMissionItemTest::cleanup();
Don Gagne's avatar
Don Gagne committed
111 112
}

113 114
void SimpleMissionItemTest::_testEditorFacts(void)
{
115
    PlanMasterController fwMasterController(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING);
116

117 118 119 120
    for (size_t i=0; i<sizeof(_rgItemInfo)/sizeof(_rgItemInfo[0]); i++) {
        const ItemInfo_t* info = &_rgItemInfo[i];
        const ItemExpected_t* expected = &_rgItemExpected[i];
        
Don Gagne's avatar
Don Gagne committed
121
        qDebug() << "Command" << info->command;
122 123 124 125 126 127 128 129 130 131 132 133 134
        
        MissionItem missionItem(1,              // sequence number
                                info->command,
                                info->frame,
                                10.1234567,     // param 1-7
                                20.1234567,
                                30.1234567,
                                40.1234567,
                                50.1234567,
                                60.1234567,
                                70.1234567,
                                true,           // autoContinue
                                false);         // isCurrentItem
135
        SimpleMissionItem simpleMissionItem(&fwMasterController, false /* flyView */, missionItem, nullptr);
136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154

        // Validate that the fact values are correctly returned

        size_t factCount = 0;
        for (int i=0; i<simpleMissionItem.textFieldFacts()->count(); i++) {
            Fact* fact = qobject_cast<Fact*>(simpleMissionItem.textFieldFacts()->get(i));
            
            bool found = false;
            for (size_t j=0; j<expected->cFactValues; j++) {
                const FactValue_t* factValue = &expected->rgFactValues[j];
                
                if (factValue->name == fact->name()) {
                    QCOMPARE(fact->rawValue().toDouble(), factValue->value);
                    factCount ++;
                    found = true;
                    break;
                }
            }
            
155
            qDebug() << "textFieldFact" << fact->name();
156 157 158 159
            QVERIFY(found);
        }
        QCOMPARE(factCount, expected->cFactValues);

160 161 162 163
        if (!qIsNaN(expected->altValue)) {
            QCOMPARE(simpleMissionItem.altitudeMode(), expected->altMode);
            QCOMPARE(simpleMissionItem.altitude()->rawValue().toDouble(), expected->altValue);
        }
164 165 166 167 168
    }
}

void SimpleMissionItemTest::_testDefaultValues(void)
{
169
    SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */, nullptr);
170 171 172

    item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
    item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
173
    QCOMPARE(item.missionItem().param7(), qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble());
174 175 176 177
}

void SimpleMissionItemTest::_testSignals(void)
{
178
    MissionItem& missionItem = _simpleItem->missionItem();
179

180 181 182 183
    // Check that changing to the same coordinate does not signal
    _simpleItem->setCoordinate(QGeoCoordinate(missionItem.param5(), missionItem.param6(), missionItem.param7()));
    QVERIFY(_spyVisualItem->checkNoSignals());
    QVERIFY(_spySimpleItem->checkNoSignals());
184 185 186 187 188 189

    // Check coordinateChanged signalling. Calling setCoordinate should trigger:
    //      coordinateChanged
    //      dirtyChanged

    // Check that actually changing coordinate signals correctly
190 191 192 193 194 195
    _simpleItem->setCoordinate(QGeoCoordinate(missionItem.param5() + 1, missionItem.param6(), missionItem.param7()));
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(coordinateChangedMask | dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
    _simpleItem->setCoordinate(QGeoCoordinate(missionItem.param5(), missionItem.param6() + 1, missionItem.param7()));
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(coordinateChangedMask | dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
196 197

    // Altitude in coordinate is not used in setCoordinate
198
    _simpleItem->setCoordinate(QGeoCoordinate(missionItem.param5(), missionItem.param6(), missionItem.param7() + 1));
199 200
    QVERIFY(_spyVisualItem->checkNoSignals());
    QVERIFY(_spySimpleItem->checkNoSignals());
201
    _spyVisualItem->clearAllSignals();
202 203 204

    // Check dirtyChanged signalling

205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225
    missionItem.setParam1(missionItem.param1());
    QVERIFY(_spyVisualItem->checkNoSignals());
    missionItem.setParam2(missionItem.param2());
    QVERIFY(_spyVisualItem->checkNoSignals());
    missionItem.setParam3(missionItem.param3());
    QVERIFY(_spyVisualItem->checkNoSignals());
    missionItem.setParam4(missionItem.param4());
    QVERIFY(_spyVisualItem->checkNoSignals());

    missionItem.setParam1(missionItem.param1() + 1);
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
    missionItem.setParam1(missionItem.param2() + 1);
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
    missionItem.setParam1(missionItem.param3() + 1);
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
    missionItem.setParam1(missionItem.param4() + 1);
    QVERIFY(_spyVisualItem->checkOnlySignalByMask(dirtyChangedMask));
    _spyVisualItem->clearAllSignals();
226

227
    _simpleItem->setAltitudeMode(_simpleItem->altitudeMode() == QGroundControlQmlGlobal::AltitudeModeRelative ? QGroundControlQmlGlobal::AltitudeModeAbsolute : QGroundControlQmlGlobal::AltitudeModeRelative);
228
    QVERIFY(_spySimpleItem->checkOnlySignalByMask(dirtyChangedMask | friendlyEditAllowedChangedMask | altitudeModeChangedMask | coordinateHasRelativeAltitudeChangedMask));
229 230 231 232 233 234 235 236 237
    _spySimpleItem->clearAllSignals();
    _spyVisualItem->clearAllSignals();

    // Check commandChanged signalling. Call setCommand should trigger:
    //      commandChanged
    //      commandNameChanged
    //      dirtyChanged
    //      coordinateChanged - since altitude will be set back to default

238
    _simpleItem->setCommand(MAV_CMD_NAV_WAYPOINT);
239 240 241
    QVERIFY(_spyVisualItem->checkNoSignals());
    QVERIFY(_spySimpleItem->checkNoSignals());

242
    _simpleItem->setCommand(MAV_CMD_NAV_LOITER_TIME);
243 244 245 246
    QVERIFY(_spySimpleItem->checkSignalsByMask(commandChangedMask));
    QVERIFY(_spyVisualItem->checkSignalsByMask(commandNameChangedMask | dirtyChangedMask | coordinateChangedMask));
}

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
void SimpleMissionItemTest::_testCameraSectionDirty(void)
{
    CameraSection* cameraSection = _simpleItem->cameraSection();

    QVERIFY(!cameraSection->dirty());
    QVERIFY(!_simpleItem->dirty());

    // Dirtying the camera section should also dirty the item
    cameraSection->setDirty(true);
    QVERIFY(_simpleItem->dirty());

    // Clearing the dirty bit from the item should also clear the dirty bit on the camera section
    _simpleItem->setDirty(false);
    QVERIFY(!cameraSection->dirty());
}

void SimpleMissionItemTest::_testSpeedSectionDirty(void)
{
    SpeedSection* speedSection = _simpleItem->speedSection();

    QVERIFY(!speedSection->dirty());
    QVERIFY(!_simpleItem->dirty());

    // Dirtying the speed section should also dirty the item
    speedSection->setDirty(true);
    QVERIFY(_simpleItem->dirty());

    // Clearing the dirty bit from the item should also clear the dirty bit on the camera section
    _simpleItem->setDirty(false);
    QVERIFY(!speedSection->dirty());
}

279
void SimpleMissionItemTest::_testCameraSection(void)
280
{
281 282 283 284 285 286 287 288 289 290 291 292 293 294
    // No gimbal yaw to start with
    QVERIFY(qIsNaN(_simpleItem->specifiedGimbalYaw()));
    QVERIFY(qIsNaN(_simpleItem->missionGimbalYaw()));
    QCOMPARE(_simpleItem->dirty(), false);

    double gimbalYaw = 10.1234;
    _simpleItem->cameraSection()->setSpecifyGimbal(true);
    _simpleItem->cameraSection()->gimbalYaw()->setRawValue(gimbalYaw);
    QCOMPARE(_simpleItem->specifiedGimbalYaw(), gimbalYaw);
    QVERIFY(qIsNaN(_simpleItem->missionGimbalYaw()));
    QCOMPARE(_spyVisualItem->checkSignalsByMask(specifiedGimbalYawChangedMask), true);
    QCOMPARE(_simpleItem->dirty(), true);
}

295

296 297 298 299 300 301 302 303 304 305 306 307
void SimpleMissionItemTest::_testSpeedSection(void)
{
    // No flight speed
    QVERIFY(qIsNaN(_simpleItem->specifiedFlightSpeed()));
    QCOMPARE(_simpleItem->dirty(), false);

    double flightSpeed = 10.1234;
    _simpleItem->speedSection()->setSpecifyFlightSpeed(true);
    _simpleItem->speedSection()->flightSpeed()->setRawValue(flightSpeed);
    QCOMPARE(_simpleItem->specifiedFlightSpeed(), flightSpeed);
    QCOMPARE(_spyVisualItem->checkSignalsByMask(specifiedFlightSpeedChangedMask), true);
    QCOMPARE(_simpleItem->dirty(), true);
308
}
309 310 311 312 313

void SimpleMissionItemTest::_testAltitudePropogation(void)
{
    // Make sure that changes to altitude propogate to param 7 of the mission item

314
    _simpleItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeModeRelative);
315 316 317 318
    _simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1);
    QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7());
    QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL_RELATIVE_ALT);

319
    _simpleItem->setAltitudeMode(QGroundControlQmlGlobal::AltitudeModeAbsolute);
320 321 322 323
    _simpleItem->altitude()->setRawValue(_simpleItem->altitude()->rawValue().toDouble() + 1);
    QCOMPARE(_simpleItem->altitude()->rawValue().toDouble(), _simpleItem->missionItem().param7());
    QCOMPARE(_simpleItem->missionItem().frame(), MAV_FRAME_GLOBAL);
}