Commit f34a7c6e authored by Don Gagne's avatar Don Gagne

Fix unit tests

parent 0adf8caa
...@@ -561,13 +561,13 @@ QString MissionItem::commandDescription(void) ...@@ -561,13 +561,13 @@ QString MissionItem::commandDescription(void)
description = "Travel to a position and Loiter around the specified radius for an amount of time."; description = "Travel to a position and Loiter around the specified radius for an amount of time.";
break; break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
description = "Send the vehicle back to the home position set when armed."; description = "Send the vehicle back to the home position.";
break; break;
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
description = "Land vehicle at the current location."; description = "Land vehicle at the specified location.";
break; break;
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
description = "Lift off from the ground and travel to the specified position."; description = "Take off from the ground and travel towards the specified position.";
break; break;
case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DELAY:
description = "Delay"; description = "Delay";
......
...@@ -101,6 +101,9 @@ public: ...@@ -101,6 +101,9 @@ public:
double headingDegrees(void) const; double headingDegrees(void) const;
void setHeadingDegrees(double headingDegrees); void setHeadingDegrees(double headingDegrees);
// This is public for unit testing
double _yawRadians(void) const;
QStringList commandNames(void); QStringList commandNames(void);
QString commandName(void); QString commandName(void);
QString commandDescription(void); QString commandDescription(void);
...@@ -251,7 +254,6 @@ private slots: ...@@ -251,7 +254,6 @@ private slots:
private: private:
QString _oneDecimalString(double value); QString _oneDecimalString(double value);
void _connectSignals(void); void _connectSignals(void);
double _yawRadians(void) const;
void _setYawRadians(double yawRadians); void _setYawRadians(double yawRadians);
private: private:
......
...@@ -27,63 +27,46 @@ ...@@ -27,63 +27,46 @@
UT_REGISTER_TEST(MissionItemTest) UT_REGISTER_TEST(MissionItemTest)
const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = { const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = {
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_WAYPOINT, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_UNLIM, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_UNLIM, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TURNS, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TURNS, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TIME, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LOITER_TIME, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LAND, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LAND, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_TAKEOFF, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_TAKEOFF, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_CONDITION_DELAY, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_CONDITION_DELAY, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_MISSION },
{ 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_DO_JUMP, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION }, { 1, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_DO_JUMP, 10.0, 20.0, 30.0, 1.0, true, false, MAV_FRAME_MISSION },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesWaypoint[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesWaypoint[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 },
{ "Radius:", 20.0 },
{ "Hold:", 10.0 }, { "Hold:", 10.0 },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterUnlim[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterUnlim[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 },
{ "Radius:", 30.0 }, { "Radius:", 30.0 },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterTurns[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterTurns[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 },
{ "Radius:", 30.0 }, { "Radius:", 30.0 },
{ "Turns:", 10.0 }, { "Turns:", 10.0 },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterTime[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterTime[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 },
{ "Radius:", 30.0 }, { "Radius:", 30.0 },
{ "Seconds:", 10.0 }, { "Seconds:", 10.0 },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLand[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLand[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 }, { "Heading:", 1.0 },
}; };
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesTakeoff[] = { const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesTakeoff[] = {
{ "Latitude:", -10.0 },
{ "Longitude:", -20.0 },
{ "Altitude:", -30.0 }, { "Altitude:", -30.0 },
{ "Heading:", 40.0 }, { "Heading:", 1.0 },
{ "Pitch:", 10.0 }, { "Pitch:", 10.0 },
}; };
...@@ -97,14 +80,14 @@ const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesDoJump[] = { ...@@ -97,14 +80,14 @@ const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesDoJump[] = {
}; };
const MissionItemTest::ItemExpected_t MissionItemTest::_rgItemExpected[] = { const MissionItemTest::ItemExpected_t MissionItemTest::_rgItemExpected[] = {
{ "1\t0\t3\t16\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesWaypoint)/sizeof(MissionItemTest::_rgFactValuesWaypoint[0]), MissionItemTest::_rgFactValuesWaypoint }, { "1\t0\t3\t16\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesWaypoint)/sizeof(MissionItemTest::_rgFactValuesWaypoint[0]), MissionItemTest::_rgFactValuesWaypoint },
{ "1\t0\t3\t17\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(MissionItemTest::_rgFactValuesLoiterUnlim[0]), MissionItemTest::_rgFactValuesLoiterUnlim }, { "1\t0\t3\t17\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(MissionItemTest::_rgFactValuesLoiterUnlim[0]), MissionItemTest::_rgFactValuesLoiterUnlim },
{ "1\t0\t3\t18\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterTurns)/sizeof(MissionItemTest::_rgFactValuesLoiterTurns[0]), MissionItemTest::_rgFactValuesLoiterTurns }, { "1\t0\t3\t18\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterTurns)/sizeof(MissionItemTest::_rgFactValuesLoiterTurns[0]), MissionItemTest::_rgFactValuesLoiterTurns },
{ "1\t0\t3\t19\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterTime)/sizeof(MissionItemTest::_rgFactValuesLoiterTime[0]), MissionItemTest::_rgFactValuesLoiterTime }, { "1\t0\t3\t19\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLoiterTime)/sizeof(MissionItemTest::_rgFactValuesLoiterTime[0]), MissionItemTest::_rgFactValuesLoiterTime },
{ "1\t0\t3\t21\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLand)/sizeof(MissionItemTest::_rgFactValuesLand[0]), MissionItemTest::_rgFactValuesLand }, { "1\t0\t3\t21\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesLand)/sizeof(MissionItemTest::_rgFactValuesLand[0]), MissionItemTest::_rgFactValuesLand },
{ "1\t0\t3\t22\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesTakeoff)/sizeof(MissionItemTest::_rgFactValuesTakeoff[0]), MissionItemTest::_rgFactValuesTakeoff }, { "1\t0\t3\t22\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesTakeoff)/sizeof(MissionItemTest::_rgFactValuesTakeoff[0]), MissionItemTest::_rgFactValuesTakeoff },
{ "1\t0\t2\t112\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesConditionDelay)/sizeof(MissionItemTest::_rgFactValuesConditionDelay[0]), MissionItemTest::_rgFactValuesConditionDelay }, { "1\t0\t2\t112\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesConditionDelay)/sizeof(MissionItemTest::_rgFactValuesConditionDelay[0]), MissionItemTest::_rgFactValuesConditionDelay },
{ "1\t0\t2\t177\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesDoJump)/sizeof(MissionItemTest::_rgFactValuesDoJump[0]), MissionItemTest::_rgFactValuesDoJump }, { "1\t0\t2\t177\t10\t20\t30\t1\t-10\t-20\t-30\t1\r\n", sizeof(MissionItemTest::_rgFactValuesDoJump)/sizeof(MissionItemTest::_rgFactValuesDoJump[0]), MissionItemTest::_rgFactValuesDoJump },
}; };
MissionItemTest::MissionItemTest(void) MissionItemTest::MissionItemTest(void)
...@@ -149,7 +132,11 @@ void MissionItemTest::_test(void) ...@@ -149,7 +132,11 @@ void MissionItemTest::_test(void)
if (factValue->name == fact->name()) { if (factValue->name == fact->name()) {
qDebug() << factValue->name; qDebug() << factValue->name;
if (strcmp(factValue->name, "Heading:") == 0) {
QCOMPARE(fact->value().toDouble() * (M_PI / 180.0), item->_yawRadians());
} else {
QCOMPARE(fact->value().toDouble(), factValue->value); QCOMPARE(fact->value().toDouble(), factValue->value);
}
factCount ++; factCount ++;
found = true; found = true;
break; break;
...@@ -158,6 +145,7 @@ void MissionItemTest::_test(void) ...@@ -158,6 +145,7 @@ void MissionItemTest::_test(void)
QVERIFY(found); QVERIFY(found);
} }
qDebug() << info->command;
QCOMPARE(factCount, expected->cFactValues); QCOMPARE(factCount, expected->cFactValues);
// Validate that loading is working correctly // Validate that loading is working correctly
......
...@@ -72,7 +72,7 @@ FlightDisplayView { ...@@ -72,7 +72,7 @@ FlightDisplayView {
onShowSetupFirmware: setupViewLoader.item.showFirmwarePanel() onShowSetupFirmware: setupViewLoader.item.showFirmwarePanel()
onShowSetupParameters: setupViewLoader.item.showParametersPanel() onShowSetupParameters: setupViewLoader.item.showParametersPanel()
onShowSetupSummary: setupViewLoader.item.showSummaryPanel() onShowSetupSummary: setupViewLoader.item.showSummaryPanel()
onShowSetupVehicleComponent: setupViewLoader.item.showVehicleComponentPanel(vechicleComponent) onShowSetupVehicleComponent: setupViewLoader.item.showVehicleComponentPanel(vehicleComponent)
} }
MainToolBar { MainToolBar {
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment