Browse Source

More comprehensive testing of editor facts

QGC4.4
DonLakeFlyer 5 years ago
parent
commit
aece8fa6af
  1. 143
      src/MissionManager/SimpleMissionItemTest.cc
  2. 49
      src/MissionManager/SimpleMissionItemTest.h

143
src/MissionManager/SimpleMissionItemTest.cc

@ -7,14 +7,13 @@
* *
****************************************************************************/ ****************************************************************************/
#include "SimpleMissionItemTest.h" #include "SimpleMissionItemTest.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h" #include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h" #include "SettingsManager.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = { static const ItemInfo_t _rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL }, { MAV_CMD_NAV_LOITER_UNLIM, MAV_FRAME_GLOBAL },
{ MAV_CMD_NAV_LOITER_TURNS, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { MAV_CMD_NAV_LOITER_TURNS, MAV_FRAME_GLOBAL_RELATIVE_ALT },
@ -24,42 +23,48 @@ const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_DO_JUMP, MAV_FRAME_MISSION }, { MAV_CMD_DO_JUMP, MAV_FRAME_MISSION },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesWaypoint[] = { static const FactValue_t _rgFactValuesWaypoint[] = {
{ "Hold", 10.1234567 }, { "Hold", QGCMAVLink::VehicleClassMultiRotor, false, 1 },
{ "Yaw", QGCMAVLink::VehicleClassMultiRotor, true, 4 },
};
static const FactValue_t _rgFactValuesLoiterUnlim[] = {
{ "Radius", QGCMAVLink::VehicleClassFixedWing, false, 3 },
{ "Yaw", QGCMAVLink::VehicleClassMultiRotor, true, 4 },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterUnlim[] = { static const FactValue_t _rgFactValuesLoiterTurns[] = {
{ "Radius", 30.1234567 }, { "Turns", QGCMAVLink::VehicleClassFixedWing, false, 1 },
{ "Radius", QGCMAVLink::VehicleClassFixedWing, false, 3 },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTurns[] = { static const FactValue_t _rgFactValuesLoiterTime[] = {
{ "Radius", 30.1234567 }, { "Loiter Time", QGCMAVLink::VehicleClassGeneric, false, 1 },
{ "Turns", 10.1234567 }, { "Radius", QGCMAVLink::VehicleClassFixedWing, false, 3 },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTime[] = { static const FactValue_t _rgFactValuesLand[] = {
{ "Radius", 30.1234567 }, { "Yaw", QGCMAVLink::VehicleClassMultiRotor, true, 4 },
{ "Loiter Time", 10.1234567 },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesTakeoff[] = { static const FactValue_t _rgFactValuesTakeoff[] = {
{ "Pitch", 10.1234567 }, { "Pitch", QGCMAVLink::VehicleClassFixedWing, false, 1 },
{ "Yaw", QGCMAVLink::VehicleClassMultiRotor, true, 4 },
}; };
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesDoJump[] = { static const FactValue_t _rgFactValuesDoJump[] = {
{ "Item #", 10.1234567 }, { "Item #", QGCMAVLink::VehicleClassGeneric, false, 1 },
{ "Repeat", 20.1234567 }, { "Repeat", QGCMAVLink::VehicleClassGeneric, false, 2 },
}; };
const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpected[] = { const ItemExpected_t _rgItemExpected[] = {
// Text field facts count Fact Values Altitude Altitude Mode { sizeof(_rgFactValuesWaypoint)/sizeof(_rgFactValuesWaypoint[0]), _rgFactValuesWaypoint, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint)/sizeof(SimpleMissionItemTest::_rgFactValuesWaypoint[0]), SimpleMissionItemTest::_rgFactValuesWaypoint, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, { sizeof(_rgFactValuesLoiterUnlim)/sizeof(_rgFactValuesLoiterUnlim[0]), _rgFactValuesLoiterUnlim, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, { sizeof(_rgFactValuesLoiterTurns)/sizeof(_rgFactValuesLoiterTurns[0]), _rgFactValuesLoiterTurns, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, { sizeof(_rgFactValuesLoiterTime)/sizeof(_rgFactValuesLoiterTime[0]), _rgFactValuesLoiterTime, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, { sizeof(_rgFactValuesLand)/sizeof(_rgFactValuesLand[0]), _rgFactValuesLand, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ 0, nullptr, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative }, { sizeof(_rgFactValuesTakeoff)/sizeof(_rgFactValuesTakeoff[0]), _rgFactValuesTakeoff, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute }, { sizeof(_rgFactValuesDoJump)/sizeof(_rgFactValuesDoJump[0]), _rgFactValuesDoJump, qQNaN(), QGroundControlQmlGlobal::AltitudeModeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), QGroundControlQmlGlobal::AltitudeModeRelative },
}; };
SimpleMissionItemTest::SimpleMissionItemTest(void) SimpleMissionItemTest::SimpleMissionItemTest(void)
@ -109,16 +114,42 @@ void SimpleMissionItemTest::cleanup(void)
VisualMissionItemTest::cleanup(); VisualMissionItemTest::cleanup();
} }
void SimpleMissionItemTest::_testEditorFacts(void) bool SimpleMissionItemTest::_classMatch(QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t testClass)
{
return vehicleClass == QGCMAVLink::VehicleClassGeneric || vehicleClass == testClass;
}
void SimpleMissionItemTest::_testEditorFactsWorker(QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t vtolMode, const ItemExpected_t* rgExpected)
{ {
PlanMasterController fwMasterController(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING); qDebug() << "vehicleClass:vtolMode" << QGCMAVLink::vehicleClassToString(vehicleClass) << QGCMAVLink::vehicleClassToString(vtolMode);
PlanMasterController planController(MAV_AUTOPILOT_PX4, QGCMAVLink::vehicleClassToMavType(vehicleClass));
QGCMAVLink::VehicleClass_t commandVehicleClass = vtolMode == QGCMAVLink::VehicleClassGeneric ? vehicleClass : vtolMode;
for (size_t i=0; i<sizeof(_rgItemInfo)/sizeof(_rgItemInfo[0]); i++) { for (size_t i=0; i<sizeof(_rgItemInfo)/sizeof(_rgItemInfo[0]); i++) {
const ItemInfo_t* info = &_rgItemInfo[i]; const ItemInfo_t* info = &_rgItemInfo[i];
const ItemExpected_t* expected = &_rgItemExpected[i]; const ItemExpected_t* expected = &rgExpected[i];
qDebug() << "Command" << info->command; qDebug() << "Command" << info->command;
// Determine how many fact values we should get back
int cExpectedTextFieldFacts = 0;
int cExpectedNaNFieldFacts = 0;
for (size_t j=0; j<expected->cFactValues; j++) {
const FactValue_t* factValue = &expected->rgFactValues[j];
if (!_classMatch(factValue->vehicleClass, commandVehicleClass)) {
continue;
}
if (factValue->nanValue) {
cExpectedNaNFieldFacts++;
} else {
cExpectedTextFieldFacts++;
}
}
MissionItem missionItem(1, // sequence number MissionItem missionItem(1, // sequence number
info->command, info->command,
info->frame, info->frame,
@ -131,11 +162,18 @@ void SimpleMissionItemTest::_testEditorFacts(void)
70.1234567, 70.1234567,
true, // autoContinue true, // autoContinue
false); // isCurrentItem false); // isCurrentItem
SimpleMissionItem simpleMissionItem(&fwMasterController, false /* flyView */, missionItem, nullptr); SimpleMissionItem simpleMissionItem(&planController, false /* flyView */, missionItem, nullptr);
MissionController::MissionFlightStatus_t missionFlightStatus;
missionFlightStatus.vtolMode = vtolMode;
missionFlightStatus.vehicleSpeed = 10;
missionFlightStatus.gimbalYaw = qQNaN();
missionFlightStatus.gimbalPitch = qQNaN();
simpleMissionItem.setMissionFlightStatus(missionFlightStatus);
// Validate that the fact values are correctly returned // Validate that the fact values are correctly returned
size_t factCount = 0; int foundTextFieldCount = 0;
for (int i=0; i<simpleMissionItem.textFieldFacts()->count(); i++) { for (int i=0; i<simpleMissionItem.textFieldFacts()->count(); i++) {
Fact* fact = qobject_cast<Fact*>(simpleMissionItem.textFieldFacts()->get(i)); Fact* fact = qobject_cast<Fact*>(simpleMissionItem.textFieldFacts()->get(i));
@ -143,9 +181,13 @@ void SimpleMissionItemTest::_testEditorFacts(void)
for (size_t j=0; j<expected->cFactValues; j++) { for (size_t j=0; j<expected->cFactValues; j++) {
const FactValue_t* factValue = &expected->rgFactValues[j]; const FactValue_t* factValue = &expected->rgFactValues[j];
if (!_classMatch(factValue->vehicleClass, commandVehicleClass)) {
continue;
}
if (factValue->name == fact->name()) { if (factValue->name == fact->name()) {
QCOMPARE(fact->rawValue().toDouble(), factValue->value); QCOMPARE(fact->rawValue().toDouble(), (factValue->paramIndex * 10.0) + 0.1234567);
factCount ++; foundTextFieldCount ++;
found = true; found = true;
break; break;
} }
@ -154,7 +196,32 @@ void SimpleMissionItemTest::_testEditorFacts(void)
qDebug() << "textFieldFact" << fact->name(); qDebug() << "textFieldFact" << fact->name();
QVERIFY(found); QVERIFY(found);
} }
QCOMPARE(factCount, expected->cFactValues); QCOMPARE(foundTextFieldCount, cExpectedTextFieldFacts);
int foundNaNFieldCount = 0;
for (int i=0; i<simpleMissionItem.nanFacts()->count(); i++) {
Fact* fact = qobject_cast<Fact*>(simpleMissionItem.nanFacts()->get(i));
bool found = false;
for (size_t j=0; j<expected->cFactValues; j++) {
const FactValue_t* factValue = &expected->rgFactValues[j];
if (!_classMatch(factValue->vehicleClass, commandVehicleClass)) {
continue;
}
if (factValue->name == fact->name()) {
QCOMPARE(fact->rawValue().toDouble(), (factValue->paramIndex * 10.0) + 0.1234567);
foundNaNFieldCount ++;
found = true;
break;
}
}
qDebug() << "nanFieldFact" << fact->name();
QVERIFY(found);
}
QCOMPARE(foundNaNFieldCount, cExpectedNaNFieldFacts);
if (!qIsNaN(expected->altValue)) { if (!qIsNaN(expected->altValue)) {
QCOMPARE(simpleMissionItem.altitudeMode(), expected->altMode); QCOMPARE(simpleMissionItem.altitudeMode(), expected->altMode);
@ -163,6 +230,14 @@ void SimpleMissionItemTest::_testEditorFacts(void)
} }
} }
void SimpleMissionItemTest::_testEditorFacts(void)
{
_testEditorFactsWorker(QGCMAVLink::VehicleClassMultiRotor, QGCMAVLink::VehicleClassGeneric, _rgItemExpected);
_testEditorFactsWorker(QGCMAVLink::VehicleClassFixedWing, QGCMAVLink::VehicleClassGeneric, _rgItemExpected);
_testEditorFactsWorker(QGCMAVLink::VehicleClassVTOL, QGCMAVLink::VehicleClassMultiRotor, _rgItemExpected);
_testEditorFactsWorker(QGCMAVLink::VehicleClassVTOL, QGCMAVLink::VehicleClassFixedWing, _rgItemExpected);
}
void SimpleMissionItemTest::_testDefaultValues(void) void SimpleMissionItemTest::_testDefaultValues(void)
{ {
SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */, nullptr); SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */, nullptr);

49
src/MissionManager/SimpleMissionItemTest.h

@ -13,6 +13,26 @@
#include "SimpleMissionItem.h" #include "SimpleMissionItem.h"
/// Unit test for SimpleMissionItem /// Unit test for SimpleMissionItem
typedef struct {
MAV_CMD command;
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
QGCMAVLink::VehicleClass_t vehicleClass;
bool nanValue;
int paramIndex;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
double altValue;
QGroundControlQmlGlobal::AltitudeMode altMode;
} ItemExpected_t;
class SimpleMissionItemTest : public VisualMissionItemTest class SimpleMissionItemTest : public VisualMissionItemTest
{ {
Q_OBJECT Q_OBJECT
@ -58,35 +78,10 @@ private:
static const size_t cSimpleItemSignals = maxSignalIndex; static const size_t cSimpleItemSignals = maxSignalIndex;
const char* rgSimpleItemSignals[cSimpleItemSignals]; const char* rgSimpleItemSignals[cSimpleItemSignals];
typedef struct { void _testEditorFactsWorker (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t vtolMode, const ItemExpected_t* rgExpected);
MAV_CMD command; bool _classMatch (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t testClass);
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
double value;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
double altValue;
QGroundControlQmlGlobal::AltitudeMode altMode;
} ItemExpected_t;
SimpleMissionItem* _simpleItem; SimpleMissionItem* _simpleItem;
MultiSignalSpy* _spySimpleItem; MultiSignalSpy* _spySimpleItem;
MultiSignalSpy* _spyVisualItem; MultiSignalSpy* _spyVisualItem;
static const ItemInfo_t _rgItemInfo[];
static const ItemExpected_t _rgItemExpected[];
static const FactValue_t _rgFactValuesWaypoint[];
static const FactValue_t _rgFactValuesLoiterUnlim[];
static const FactValue_t _rgFactValuesLoiterTurns[];
static const FactValue_t _rgFactValuesLoiterTime[];
static const FactValue_t _rgFactValuesLand[];
static const FactValue_t _rgFactValuesTakeoff[];
static const FactValue_t _rgFactValuesConditionDelay[];
static const FactValue_t _rgFactValuesDoJump[];
}; };

Loading…
Cancel
Save