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

10 11 12 13

#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
14
#include "SimpleMissionItem.h"
Don Gagne's avatar
Don Gagne committed
15
#include "MissionSettingsItem.h"
16 17 18
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "AppSettings.h"
19 20

MissionControllerTest::MissionControllerTest(void)
Don Gagne's avatar
Don Gagne committed
21 22 23
    : _multiSpyMissionController(NULL)
    , _multiSpyMissionItem(NULL)
    , _missionController(NULL)
24 25 26 27 28 29
{
    
}

void MissionControllerTest::cleanup(void)
{
30 31
    delete _masterController;
    _masterController = NULL;
32

Don Gagne's avatar
Don Gagne committed
33 34 35 36 37 38
    delete _multiSpyMissionController;
    _multiSpyMissionController = NULL;

    delete _multiSpyMissionItem;
    _multiSpyMissionItem = NULL;

39 40 41 42 43 44 45
    MissionControllerManagerTest::cleanup();
}

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

Don Gagne's avatar
Don Gagne committed
46 47
    // VisualMissionItem signals
    _rgVisualItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
Don Gagne's avatar
Don Gagne committed
48 49

    // MissionController signals
50
    _rgMissionControllerSignals[visualItemsChangedSignalIndex] =    SIGNAL(visualItemsChanged());
51
    _rgMissionControllerSignals[waypointLinesChangedSignalIndex] =  SIGNAL(waypointLinesChanged());
52

53 54 55 56
    // Master controller pulls offline vehicle info from settings
    qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->setRawValue(firmwareType);
    _masterController = new PlanMasterController(this);
    _missionController = _masterController->missionController();
57

Don Gagne's avatar
Don Gagne committed
58 59 60
    _multiSpyMissionController = new MultiSignalSpy();
    Q_CHECK_PTR(_multiSpyMissionController);
    QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
61

62
    _masterController->start(false /* flyView */);
63 64

    // All signals should some through on start
65
    QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
Don Gagne's avatar
Don Gagne committed
66
    _multiSpyMissionController->clearAllSignals();
67

68 69
    QmlObjectListModel* visualItems = _missionController->visualItems();
    QVERIFY(visualItems);
70 71

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

Don Gagne's avatar
Don Gagne committed
74 75 76 77 78 79
    // Mission Settings should be in first slot
    MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);
    QVERIFY(settingsItem);

    // Offline vehicle, so no home position
    QCOMPARE(settingsItem->coordinate().isValid(), false);
80

Don Gagne's avatar
Don Gagne committed
81 82
    // Empty mission, so no child items possible
    QCOMPARE(settingsItem->childItems()->count(), 0);
83 84 85 86 87 88 89 90 91 92 93 94 95 96

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

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

97 98
    QmlObjectListModel* visualItems = _missionController->visualItems();
    QVERIFY(visualItems);
Don Gagne's avatar
Don Gagne committed
99 100
    VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(0);
    QVERIFY(visualItem);
101

Don Gagne's avatar
Don Gagne committed
102
    _setupVisualItemSignals(visualItem);
103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
}

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);

121
    _missionController->insertSimpleMissionItem(coordinate, _missionController->visualItems()->count());
122

Don Gagne's avatar
Don Gagne committed
123
    QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
124

125 126
    QmlObjectListModel* visualItems = _missionController->visualItems();
    QVERIFY(visualItems);
127

128
    QCOMPARE(visualItems->count(), 2);
129

Don Gagne's avatar
Don Gagne committed
130 131 132 133
    MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);
    SimpleMissionItem* simpleItem = visualItems->value<SimpleMissionItem*>(1);
    QVERIFY(settingsItem);
    QVERIFY(simpleItem);
134

135
    QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF);
Don Gagne's avatar
Don Gagne committed
136
    QCOMPARE(simpleItem->childItems()->count(), 0);
137

138 139
    // Planned home position should always be set after first item
    QVERIFY(settingsItem->coordinate().isValid());
140

Don Gagne's avatar
Don Gagne committed
141 142 143 144 145
    // ArduPilot takeoff command has no coordinate, so should be child item
    QCOMPARE(settingsItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0);

    // Check waypoint line from home to takeoff
    int expectedLineCount = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : 1;
146 147 148 149 150 151 152 153 154 155 156 157 158 159 160
    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
161

162
#if 0
Don Gagne's avatar
Don Gagne committed
163 164 165 166 167
void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
{
    // Start offline and add item
    _missionController = new MissionController();
    Q_CHECK_PTR(_missionController);
168
    _missionController->start(false /* flyView */);
169
    _missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
Don Gagne's avatar
Don Gagne committed
170 171 172 173

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

Don Gagne's avatar
Don Gagne committed
174 175 176 177 178
#if 1
    // Due to current limitations, offline items will go away
    QCOMPARE(_missionController->visualItems()->count(), 1);
#else
    //Make sure our offline mission items are still there
179
    QCOMPARE(_missionController->visualItems()->count(), 2);
Don Gagne's avatar
Don Gagne committed
180
#endif
Don Gagne's avatar
Don Gagne committed
181 182 183 184 185 186 187 188 189 190 191
}

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

void MissionControllerTest::_testOfflineToOnlinePX4(void)
{
    _testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
192
#endif
Don Gagne's avatar
Don Gagne committed
193

Don Gagne's avatar
Don Gagne committed
194
void MissionControllerTest::_setupVisualItemSignals(VisualMissionItem* visualItem)
Don Gagne's avatar
Don Gagne committed
195 196 197 198 199
{
    delete _multiSpyMissionItem;

    _multiSpyMissionItem = new MultiSignalSpy();
    Q_CHECK_PTR(_multiSpyMissionItem);
Don Gagne's avatar
Don Gagne committed
200
    QCOMPARE(_multiSpyMissionItem->init(visualItem, _rgVisualItemSignals, _cVisualItemSignals), true);
Don Gagne's avatar
Don Gagne committed
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

void MissionControllerTest::_testGimbalRecalc(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_PX4);
    _missionController->insertSimpleMissionItem(QGeoCoordinate(0, 0), 1);
    _missionController->insertSimpleMissionItem(QGeoCoordinate(0, 0), 2);
    _missionController->insertSimpleMissionItem(QGeoCoordinate(0, 0), 3);
    _missionController->insertSimpleMissionItem(QGeoCoordinate(0, 0), 4);

    // No specific gimbal yaw set yet
    for (int i=1; i<_missionController->visualItems()->count(); i++) {
        VisualMissionItem* visualItem = _missionController->visualItems()->value<VisualMissionItem*>(i);
        QVERIFY(qIsNaN(visualItem->missionGimbalYaw()));
    }

    // Specify gimbal yaw on settings item should generate yaw on all items
    MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
    settingsItem->cameraSection()->setSpecifyGimbal(true);
    settingsItem->cameraSection()->gimbalYaw()->setRawValue(0.0);
    for (int i=1; i<_missionController->visualItems()->count(); i++) {
        VisualMissionItem* visualItem = _missionController->visualItems()->value<VisualMissionItem*>(i);
        QCOMPARE(visualItem->missionGimbalYaw(), 0.0);
    }
}
226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249

void MissionControllerTest::_testLoadJsonSectionAvailable(void)
{
    _initForFirmwareType(MAV_AUTOPILOT_PX4);
    _masterController->loadFromFile(":/unittest/SectionTest.plan");

    QmlObjectListModel* visualItems = _missionController->visualItems();
    QVERIFY(visualItems);
    QCOMPARE(visualItems->count(), 5);

    // Check that only waypoint items have camera and speed sections
    for (int i=1; i<visualItems->count(); i++) {
        SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(i);
        QVERIFY(item);
        if ((int)item->command() == MAV_CMD_NAV_WAYPOINT) {
            QCOMPARE(item->cameraSection()->available(), true);
            QCOMPARE(item->speedSection()->available(), true);
        } else {
            QCOMPARE(item->cameraSection()->available(), false);
            QCOMPARE(item->speedSection()->available(), false);
        }

    }
}