地面站终端 App
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

294 lines
13 KiB

/****************************************************************************
*
* (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 "SimpleMissionItemTest.h"
#include "SimpleMissionItem.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_TURNS, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_TIME, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LAND, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_TAKEOFF, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_CONDITION_DELAY, MAV_FRAME_MISSION },
{ MAV_CMD_DO_JUMP, MAV_FRAME_MISSION },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesWaypoint[] = {
8 years ago
{ "Altitude", 70.1234567 },
{ "Hold", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterUnlim[] = {
8 years ago
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTurns[] = {
8 years ago
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
{ "Turns", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTime[] = {
8 years ago
{ "Altitude", 70.1234567 },
{ "Radius", 30.1234567 },
{ "Hold", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLand[] = {
8 years ago
{ "Altitude", 70.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesTakeoff[] = {
8 years ago
{ "Pitch", 10.1234567 },
{ "Altitude", 70.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesConditionDelay[] = {
8 years ago
{ "Hold", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJump[] = {
8 years ago
{ "Item #", 10.1234567 },
{ "Repeat", 20.1234567 },
};
const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = {
{ sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLand)/sizeof(SimpleMissionItemTest::_rgFactValuesLand[0]), SimpleMissionItemTest::_rgFactValuesLand, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, true },
{ sizeof(SimpleMissionItemTest::_rgFactValuesConditionDelay)/sizeof(SimpleMissionItemTest::_rgFactValuesConditionDelay[0]), SimpleMissionItemTest::_rgFactValuesConditionDelay, false },
{ sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, false },
};
SimpleMissionItemTest::SimpleMissionItemTest(void)
8 years ago
: _offlineVehicle(NULL)
{
}
8 years ago
void SimpleMissionItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4,
MAV_TYPE_QUADROTOR,
qgcApp()->toolbox()->firmwarePluginManager(),
this);
}
void SimpleMissionItemTest::cleanup(void)
{
delete _offlineVehicle;
UnitTest::cleanup();
}
void SimpleMissionItemTest::_testEditorFacts(void)
{
Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager());
for (size_t i=0; i<sizeof(_rgItemInfo)/sizeof(_rgItemInfo[0]); i++) {
const ItemInfo_t* info = &_rgItemInfo[i];
const ItemExpected_t* expected = &_rgItemExpected[i];
8 years ago
qDebug() << "Command" << info->command;
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
SimpleMissionItem simpleMissionItem(vehicle, missionItem);
// 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;
}
}
qDebug() << fact->name();
QVERIFY(found);
}
QCOMPARE(factCount, expected->cFactValues);
int expectedCount = expected->relativeAltCheckbox ? 1 : 0;
QCOMPARE(simpleMissionItem.checkboxFacts()->count(), expectedCount);
}
delete vehicle;
}
void SimpleMissionItemTest::_testDefaultValues(void)
{
8 years ago
SimpleMissionItem item(_offlineVehicle);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
QCOMPARE(item.missionItem().param7(), qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble());
}
void SimpleMissionItemTest::_testSignals(void)
{
enum {
commandChangedIndex = 0,
frameChangedIndex,
friendlyEditAllowedChangedIndex,
headingDegreesChangedIndex,
rawEditChangedIndex,
8 years ago
coordinateChangedIndex,
exitCoordinateChangedIndex,
dirtyChangedIndex,
maxSignalIndex
};
enum {
commandChangedMask = 1 << commandChangedIndex,
frameChangedMask = 1 << frameChangedIndex,
friendlyEditAllowedChangedMask = 1 << friendlyEditAllowedChangedIndex,
headingDegreesChangedMask = 1 << headingDegreesChangedIndex,
rawEditChangedMask = 1 << rawEditChangedIndex,
8 years ago
coordinateChangedMask = 1 << coordinateChangedIndex,
exitCoordinateChangedMask = 1 << exitCoordinateChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex,
};
static const size_t cSimpleMissionItemSignals = maxSignalIndex;
const char* rgSimpleMissionItemSignals[cSimpleMissionItemSignals];
rgSimpleMissionItemSignals[commandChangedIndex] = SIGNAL(commandChanged(int));
rgSimpleMissionItemSignals[coordinateChangedIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
rgSimpleMissionItemSignals[exitCoordinateChangedIndex] = SIGNAL(exitCoordinateChanged(const QGeoCoordinate&));
rgSimpleMissionItemSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
rgSimpleMissionItemSignals[frameChangedIndex] = SIGNAL(frameChanged(int));
rgSimpleMissionItemSignals[friendlyEditAllowedChangedIndex] = SIGNAL(friendlyEditAllowedChanged(bool));
rgSimpleMissionItemSignals[headingDegreesChangedIndex] = SIGNAL(headingDegreesChanged(double));
rgSimpleMissionItemSignals[rawEditChangedIndex] = SIGNAL(rawEditChanged(bool));
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
8 years ago
SimpleMissionItem simpleMissionItem(_offlineVehicle, missionItem);
// 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.
MultiSignalSpy* multiSpy = new MultiSignalSpy();
Q_CHECK_PTR(multiSpy);
QCOMPARE(multiSpy->init(&simpleMissionItem, rgSimpleMissionItemSignals, cSimpleMissionItemSignals), true);
// Check commandChanged signalling. Call setCommand should trigger:
// commandChanged
// dirtyChanged
// coordinateChanged - since altitude will be set back to default
simpleMissionItem.setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_LOITER_TIME);
8 years ago
QVERIFY(multiSpy->checkSignalsByMask(commandChangedMask | dirtyChangedMask | coordinateChangedMask));
multiSpy->clearAllSignals();
// Check coordinateChanged signalling. Calling setCoordinate should trigger:
// coordinateChanged
// dirtyChanged
// Check that changing to the same coordinate does not signal
simpleMissionItem.setCoordinate(QGeoCoordinate(50.1234567, 60.1234567, qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble()));
QVERIFY(multiSpy->checkNoSignals());
// Check that actually changing coordinate signals correctly
simpleMissionItem.setCoordinate(QGeoCoordinate(50.1234567, 60.1234567, 70.1234567));
QVERIFY(multiSpy->checkOnlySignalByMask(coordinateChangedMask | dirtyChangedMask));
multiSpy->clearAllSignals();
// Check dirtyChanged signalling
// Reset param 1-5 for testing
simpleMissionItem.missionItem().setParam1(10.1234567);
simpleMissionItem.missionItem().setParam2(20.1234567);
simpleMissionItem.missionItem().setParam3(30.1234567);
simpleMissionItem.missionItem().setParam4(40.1234567);
multiSpy->clearAllSignals();
simpleMissionItem.missionItem().setParam1(10.1234567);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.missionItem().setParam1(20.1234567);
QVERIFY(multiSpy->checkOnlySignalByMask(dirtyChangedMask));
multiSpy->clearAllSignals();
simpleMissionItem.missionItem().setParam2(20.1234567);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.missionItem().setParam2(30.1234567);
QVERIFY(multiSpy->checkOnlySignalByMask(dirtyChangedMask));
multiSpy->clearAllSignals();
simpleMissionItem.missionItem().setParam3(30.1234567);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.missionItem().setParam3(40.1234567);
QVERIFY(multiSpy->checkOnlySignalByMask(dirtyChangedMask));
multiSpy->clearAllSignals();
simpleMissionItem.missionItem().setParam4(40.1234567);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.missionItem().setParam4(50.1234567);
QVERIFY(multiSpy->checkOnlySignalByMask(dirtyChangedMask));
multiSpy->clearAllSignals();
// Check frameChanged signalling. Calling setFrame should signal:
// frameChanged
// dirtyChanged
// friendlyEditAllowedChanged - this signal is not very smart on when it gets sent
simpleMissionItem.setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
simpleMissionItem.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
multiSpy->clearAllSignals();
simpleMissionItem.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
QVERIFY(multiSpy->checkNoSignals());
simpleMissionItem.missionItem().setFrame(MAV_FRAME_GLOBAL);
QVERIFY(multiSpy->checkOnlySignalByMask(frameChangedMask | dirtyChangedMask | friendlyEditAllowedChangedMask));
multiSpy->clearAllSignals();
}