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
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
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
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
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
181
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
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
244
245
246
247
248
249
250
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
#include "SimpleMissionItem.h"
#include "MissionSettingsItem.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "AppSettings.h"
MissionControllerTest::MissionControllerTest(void)
: _multiSpyMissionController(NULL)
, _multiSpyMissionItem(NULL)
, _missionController(NULL)
{
}
void MissionControllerTest::cleanup(void)
{
delete _masterController;
_masterController = NULL;
delete _multiSpyMissionController;
_multiSpyMissionController = NULL;
delete _multiSpyMissionItem;
_multiSpyMissionItem = NULL;
MissionControllerManagerTest::cleanup();
}
void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
// VisualMissionItem signals
_rgVisualItemSignals[coordinateChangedSignalIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
// MissionController signals
_rgMissionControllerSignals[visualItemsChangedSignalIndex] = SIGNAL(visualItemsChanged());
_rgMissionControllerSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
// Master controller pulls offline vehicle info from settings
qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->setRawValue(firmwareType);
_masterController = new PlanMasterController(this);
_missionController = _masterController->missionController();
_multiSpyMissionController = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpyMissionController);
QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
_masterController->start(true /* editMode */);
// All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
_multiSpyMissionController->clearAllSignals();
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
// Empty vehicle only has home position
QCOMPARE(visualItems->count(), 1);
// 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);
// Empty mission, so no child items possible
QCOMPARE(settingsItem->childItems()->count(), 0);
// 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
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(0);
QVERIFY(visualItem);
_setupVisualItemSignals(visualItem);
}
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->insertSimpleMissionItem(coordinate, _missionController->visualItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
QmlObjectListModel* visualItems = _missionController->visualItems();
QVERIFY(visualItems);
QCOMPARE(visualItems->count(), 2);
MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);
SimpleMissionItem* simpleItem = visualItems->value<SimpleMissionItem*>(1);
QVERIFY(settingsItem);
QVERIFY(simpleItem);
QCOMPARE(simpleItem->command(), MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
QCOMPARE(simpleItem->childItems()->count(), 0);
// If the first item added specifies a coordinate, then planned home position will be set
bool plannedHomePositionValue = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? false : true;
QCOMPARE(settingsItem->coordinate().isValid(), plannedHomePositionValue);
// 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;
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);
}
#if 0
void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
{
// Start offline and add item
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
#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
QCOMPARE(_missionController->visualItems()->count(), 2);
#endif
}
void MissionControllerTest::_testOfflineToOnlineAPM(void)
{
_testOfflineToOnlineWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}
void MissionControllerTest::_testOfflineToOnlinePX4(void)
{
_testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
}
#endif
void MissionControllerTest::_setupVisualItemSignals(VisualMissionItem* visualItem)
{
delete _multiSpyMissionItem;
_multiSpyMissionItem = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpyMissionItem);
QCOMPARE(_multiSpyMissionItem->init(visualItem, _rgVisualItemSignals, _cVisualItemSignals), true);
}
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);
}
}
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);
}
}
}