MissionControllerTest.cc 9.22 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
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"

MissionControllerTest::MissionControllerTest(void)
Don Gagne's avatar
Don Gagne committed
29 30 31
    : _multiSpyMissionController(NULL)
    , _multiSpyMissionItem(NULL)
    , _missionController(NULL)
32 33 34 35 36 37 38
{
    
}

void MissionControllerTest::cleanup(void)
{
    delete _missionController;
Don Gagne's avatar
Don Gagne committed
39
    _missionController = NULL;
40

Don Gagne's avatar
Don Gagne committed
41 42 43 44 45 46
    delete _multiSpyMissionController;
    _multiSpyMissionController = NULL;

    delete _multiSpyMissionItem;
    _multiSpyMissionItem = NULL;

47 48 49 50 51
    MissionControllerManagerTest::cleanup();
}

void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
Don Gagne's avatar
Don Gagne committed
52 53
    bool startController = false;

54 55
    MissionControllerManagerTest::_initForFirmwareType(firmwareType);

Don Gagne's avatar
Don Gagne committed
56 57 58 59 60 61 62 63 64 65 66 67 68 69
    void coordinateChanged(const QGeoCoordinate& coordinate);
    void headingDegreesChanged(double heading);
    void dirtyChanged(bool dirty);
    void homePositionValidChanged(bool homePostionValid);

    // MissionItem signals
    _rgMissionItemSignals[coordinateChangedSignalIndex] =           SIGNAL(coordinateChanged(const QGeoCoordinate&));
    _rgMissionItemSignals[homePositionValidChangedSignalIndex] =    SIGNAL(homePositionValidChanged(bool));

    // MissionController signals
    _rgMissionControllerSignals[missionItemsChangedSignalIndex] =               SIGNAL(missionItemsChanged());
    _rgMissionControllerSignals[waypointLinesChangedSignalIndex] =              SIGNAL(waypointLinesChanged());
    _rgMissionControllerSignals[liveHomePositionAvailableChangedSignalIndex] =  SIGNAL(liveHomePositionAvailableChanged(bool));
    _rgMissionControllerSignals[liveHomePositionChangedSignalIndex] =           SIGNAL(liveHomePositionChanged(const QGeoCoordinate&));
70

Don Gagne's avatar
Don Gagne committed
71 72 73 74 75
    if (!_missionController) {
        startController = true;
        _missionController = new MissionController();
        Q_CHECK_PTR(_missionController);
    }
76

Don Gagne's avatar
Don Gagne committed
77 78 79
    _multiSpyMissionController = new MultiSignalSpy();
    Q_CHECK_PTR(_multiSpyMissionController);
    QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
80

Don Gagne's avatar
Don Gagne committed
81 82 83
    if (startController) {
        _missionController->start(false /* editMode */);
    }
84 85

    // All signals should some through on start
Don Gagne's avatar
Don Gagne committed
86 87
    QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
    _multiSpyMissionController->clearAllSignals();
88 89 90 91 92 93 94

    QmlObjectListModel* missionItems = _missionController->missionItems();
    QVERIFY(missionItems);

    // Empty vehicle only has home position
    QCOMPARE(missionItems->count(), 1);

Don Gagne's avatar
Don Gagne committed
95
    // Home position should be in first slot, but not yet valid
96 97 98
    MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
    QVERIFY(homeItem);
    QCOMPARE(homeItem->homePosition(), true);
Don Gagne's avatar
Don Gagne committed
99
    QCOMPARE(homeItem->homePositionValid(), false);
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

    // Home should have no children
    QCOMPARE(homeItem->childItems()->count(), 0);

    // No waypoint lines
    QmlObjectListModel* waypointLines = _missionController->waypointLines();
    QVERIFY(waypointLines);
    QCOMPARE(waypointLines->count(), 0);

    // Should not have home position yet
    QCOMPARE(_missionController->liveHomePositionAvailable(), false);

    // AutoSync should be off by default
    QCOMPARE(_missionController->autoSync(), false);
}

void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
{
    _initForFirmwareType(firmwareType);

    // FYI: A significant amount of empty vehicle testing is in _initForFirmwareType since that
    // sets up an empty vehicle

    // APM stack doesn't support HOME_POSITION yet
    bool expectedHomePositionValid = firmwareType == MAV_AUTOPILOT_PX4 ? true : false;

    QmlObjectListModel* missionItems = _missionController->missionItems();
    QVERIFY(missionItems);
    MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
    QVERIFY(homeItem);

Don Gagne's avatar
Don Gagne committed
131 132
    _setupMissionItemSignals(homeItem);

133 134 135 136
    if (expectedHomePositionValid) {
        // Wait for the home position to show up

        if (!_missionController->liveHomePositionAvailable()) {
Don Gagne's avatar
Don Gagne committed
137 138 139
            QVERIFY(_multiSpyMissionController->waitForSignalByIndex(liveHomePositionAvailableChangedSignalIndex, 2000));
            QCOMPARE(_multiSpyMissionController->pullBoolFromSignalIndex(liveHomePositionAvailableChangedSignalIndex), true);
        }
140

Don Gagne's avatar
Don Gagne committed
141 142 143 144
        if (!homeItem->homePositionValid()) {
            QVERIFY(_multiSpyMissionItem->waitForSignalByIndex(homePositionValidChangedSignalIndex, 2000));
            QCOMPARE(_multiSpyMissionItem->pullBoolFromSignalIndex(homePositionValidChangedSignalIndex), true);
        }
145

Don Gagne's avatar
Don Gagne committed
146
        // Once the home position shows up we get a number of addititional signals
147

Don Gagne's avatar
Don Gagne committed
148 149 150
        QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask | waypointLinesChangedSignalMask), true);
        QCOMPARE(_multiSpyMissionController->checkSignalByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask), true);
        QCOMPARE(_multiSpyMissionController->checkSignalByMask(waypointLinesChangedSignalMask), false);
151

Don Gagne's avatar
Don Gagne committed
152 153 154 155
        QCOMPARE(_multiSpyMissionItem->checkSignalByMask(homePositionValidChangedSignalMask), true);

        _multiSpyMissionController->clearAllSignals();
        _multiSpyMissionItem->clearAllSignals();
156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180
    }

    QCOMPARE(homeItem->homePositionValid(), expectedHomePositionValid);
    QCOMPARE(_missionController->liveHomePositionAvailable(), expectedHomePositionValid);
    QCOMPARE(_missionController->liveHomePosition().isValid(), expectedHomePositionValid);
}

void MissionControllerTest::_testEmptyVehiclePX4(void)
{
    _testEmptyVehicleWorker(MAV_AUTOPILOT_PX4);
}

void MissionControllerTest::_testEmptyVehicleAPM(void)
{
    _testEmptyVehicleWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}

void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
{
    _initForFirmwareType(firmwareType);

    QGeoCoordinate coordinate(37.803784, -122.462276);

    _missionController->addMissionItem(coordinate);

Don Gagne's avatar
Don Gagne committed
181
    QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
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

    QmlObjectListModel* missionItems = _missionController->missionItems();
    QVERIFY(missionItems);

    QCOMPARE(missionItems->count(), 2);

    MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
    MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
    QVERIFY(homeItem);
    QVERIFY(item);

    QCOMPARE(item->command(), MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
    QCOMPARE(homeItem->childItems()->count(), 0);
    QCOMPARE(item->childItems()->count(), 0);

    int expectedLineCount;
    if (homeItem->homePositionValid()) {
        expectedLineCount = 1;
    } else {
        expectedLineCount = 0;
    }

    QmlObjectListModel* waypointLines = _missionController->waypointLines();
    QVERIFY(waypointLines);
    QCOMPARE(waypointLines->count(), expectedLineCount);
}

void MissionControllerTest::_testAddWayppointAPM(void)
{
    _testAddWaypointWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}


void MissionControllerTest::_testAddWayppointPX4(void)
{
    _testAddWaypointWorker(MAV_AUTOPILOT_PX4);
}
Don Gagne's avatar
Don Gagne committed
219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243

void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
{
    // Start offline and add item
    _missionController = new MissionController();
    Q_CHECK_PTR(_missionController);
    _missionController->start(true /* editMode */);
    _missionController->addMissionItem(QGeoCoordinate(37.803784, -122.462276));

    // Go online to empty vehicle
    MissionControllerManagerTest::_initForFirmwareType(firmwareType);

    // Make sure our offline mission items are still there
    QCOMPARE(_missionController->missionItems()->count(), 2);
}

void MissionControllerTest::_testOfflineToOnlineAPM(void)
{
    _testOfflineToOnlineWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}

void MissionControllerTest::_testOfflineToOnlinePX4(void)
{
    _testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
Don Gagne's avatar
Don Gagne committed
244 245 246 247 248 249 250 251 252

void MissionControllerTest::_setupMissionItemSignals(MissionItem* item)
{
    delete _multiSpyMissionItem;

    _multiSpyMissionItem = new MultiSignalSpy();
    Q_CHECK_PTR(_multiSpyMissionItem);
    QCOMPARE(_multiSpyMissionItem->init(item, _rgMissionItemSignals, _cMissionItemSignals), true);
}