Unverified Commit 0783e815 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8925 from DonLakeFlyer/MavCmd

Plan: Command editor json clean, unit test
parents 825c5ab6 2d164923
......@@ -474,6 +474,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/CameraSectionTest.h \
src/MissionManager/CorridorScanComplexItemTest.h \
src/MissionManager/FWLandingPatternTest.h \
src/MissionManager/MissionCommandTreeEditorTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
......@@ -520,6 +521,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/CameraSectionTest.cc \
src/MissionManager/CorridorScanComplexItemTest.cc \
src/MissionManager/FWLandingPatternTest.cc \
src/MissionManager/MissionCommandTreeEditorTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
......
......@@ -64,6 +64,7 @@
<file alias="MAVLinkInspectorPage.qml">src/AnalyzeView/MAVLinkInspectorPage.qml</file>
<file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file>
<file alias="MicrohardSettings.qml">src/Microhard/MicrohardSettings.qml</file>
<file alias="MissionCommandTreeEditorTestWindow.qml">src/MissionManager/MissionCommandTreeEditorTestWindow.qml</file>
<file alias="MissionSettingsEditor.qml">src/PlanView/MissionSettingsEditor.qml</file>
<file alias="MockLink.qml">src/ui/preferences/MockLink.qml</file>
<file alias="MockLinkSettings.qml">src/ui/preferences/MockLinkSettings.qml</file>
......
......@@ -9,36 +9,6 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
......
......@@ -9,28 +9,6 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "1,3,4"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
......
......@@ -7,22 +7,7 @@
{
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2,3,4"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "3"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"paramRemove": "4"
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"paramRemove": "4"
"paramRemove": "3,4"
},
{
"id": 21,
......@@ -33,11 +18,6 @@
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1,2,3,4"
},
{
"id": 31,
"comment": "MAV_CMD_NAV_LOITER_TO_ALT",
"paramRemove": "4"
}
]
}
{
"comment": "PX4 Pro, Any Vehicle",
"version": 1,
"fileType": "MavCmdInfo",
"comment": "PX4 Pro, Any Vehicle",
"version": 1,
"fileType": "MavCmdInfo",
"mavCmdInfo": [
{
......@@ -14,11 +14,6 @@
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1"
},
{
"id": 201,
"comment": "MAV_CMD_DO_SET_ROI",
"paramRemove": "1,2,3"
},
{
"id": 2500,
"comment": "MAV_CMD_VIDEO_START_CAPTURE",
......
{
"comment": "PX4 Pro, Fixed Wing",
"version": 1,
"fileType": "MavCmdInfo",
"comment": "PX4 Pro, Fixed Wing",
"version": 1,
"fileType": "MavCmdInfo",
"mavCmdInfo": [
]
......
......@@ -4,29 +4,5 @@
"fileType": "MavCmdInfo",
"mavCmdInfo": [
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"description": "Travel to a position and Loiter indefinitely.",
"paramRemove": "3"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"description": "Travel to a position and Loiter for a number of turns.",
"paramRemove": "3"
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"description": "Travel to a position and Loiter for an amount of time.",
"paramRemove": "3"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1",
"description": "Hover straight up to specified altitude. Then travel to specified position."
}
]
}
......@@ -41,11 +41,11 @@
"param2": {
"label": "Acceptance",
"units": "m",
"default": 3,
"default": 0,
"decimalPlaces": 2
},
"param3": {
"label": "PassThru",
"label": "Pass Radius",
"units": "m",
"default": 0,
"decimalPlaces": 2
......@@ -62,7 +62,7 @@
"id": 17,
"rawName": "MAV_CMD_NAV_LOITER_UNLIM",
"friendlyName": "Loiter",
"description": "Travel to a position and Loiter around the specified radius indefinitely.",
"description": "Travel to a position and Loiter around the specified position indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
......@@ -84,7 +84,7 @@
"id": 18,
"rawName": "MAV_CMD_NAV_LOITER_TURNS",
"friendlyName": "Loiter (turns)",
"description": "Travel to a position and Loiter around the specified radius for a number of turns.",
"description": "Travel to a position and Loiter around the specified position for a number of turns.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
......@@ -93,6 +93,13 @@
"default": 1,
"decimalPlaces": 0
},
"param2": {
"label": "Leave Loiter",
"enumStrings": "Direction of next waypoint,Any direction",
"enumValues": "1,0",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Radius",
"units": "m",
......@@ -100,27 +107,34 @@
"decimalPlaces": 2
},
"param4": {
"label": "Yaw",
"units": "deg",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 19,
"rawName": "MAV_CMD_NAV_LOITER_TIME",
"friendlyName": "Loiter (time)",
"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 position for an amount of time.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Hold",
"label": "Loiter Time",
"units": "secs",
"default": 30,
"decimalPlaces": 0
},
"param2": {
"label": "Leave Loiter",
"enumStrings": "Direction of next waypoint,Current direction",
"enumValues": "1,0",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Radius",
"units": "m",
......@@ -128,11 +142,11 @@
"decimalPlaces": 2
},
"param4": {
"label": "Yaw",
"units": "deg",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
......@@ -158,6 +172,14 @@
"default": 0,
"decimalPlaces": 2
},
"param2": {
"label": "Precision Land",
"units": "m",
"enumStrings": "Disabled,Opportunistic,Required",
"enumValues": "0,1,2",
"default": 0,
"decimalPlaces": 2
},
"param4": {
"label": "Yaw",
"units": "deg",
......@@ -218,10 +240,10 @@
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Heading wait",
"enumStrings": "False,True",
"enumValues": "0,1",
"default": 0,
"label": "Leave Loiter",
"enumStrings": "Direction of next waypoint,Any direction",
"enumValues": "1,0",
"default": 1,
"decimalPlaces": 0
},
"param2": {
......@@ -294,6 +316,14 @@
"isTakeoffCommand": true,
"friendlyEdit": true,
"category": "Basic",
"param2": {
"label": "Transition Heading",
"units": "m",
"enumStrings": "Default,Next waypoint,Takeoff,Specified,Any",
"enumValues": "0,1,2,3,4",
"default": 0,
"decimalPlaces": 0
},
"param4": {
"label": "Yaw",
"units": "deg",
......@@ -311,6 +341,13 @@
"isLandCommand": true,
"friendlyEdit": true,
"category": "Basic",
"param3": {
"label": "Approach Alt",
"units": "m",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
},
"param4": {
"label": "Yaw",
"units": "deg",
......@@ -326,7 +363,7 @@
"description": "Enable/Disabled guided mode.",
"param1": {
"label": "Enable",
"enumStrings": "Disable,Enable",
"enumStrings": "On,Off",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
......@@ -367,14 +404,14 @@
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold",
"label": "Delay",
"units": "secs",
"default": 30,
"decimalPlaces": 0
}
},
{
"id": 113,
"id": 113,
"rawName": "MAV_CMD_CONDITION_CHANGE_ALT",
"description": "Delay the mission until the specified altitide is reached.",
"friendlyName": "Wait for altitude",
......@@ -405,10 +442,10 @@
"id": 115,
"rawName": "MAV_CMD_CONDITION_YAW",
"friendlyName": "Wait for Yaw",
"description": "Delay the mission until the specified yaw is reached.",
"description": "Delay the mission until the specified heading is reached.",
"category": "Conditionals",
"param1": {
"label": "Yaw",
"label": "Heading",
"units": "deg",
"default": 0,
"decimalPlaces": 1
......@@ -1071,7 +1108,7 @@
},
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{
"id": 3000,
"id": 3000,
"rawName": "MAV_CMD_DO_VTOL_TRANSITION",
"friendlyName": "VTOL Transition",
"description": "Perform flight mode transition.",
......@@ -1079,7 +1116,7 @@
"param1": {
"label": "Mode",
"default": 3,
"enumStrings": "Hover Mode,Plane Mode",
"enumStrings": "Multi Rotor,Fixed Wing",
"enumValues": "3,4"
}
},
......
......@@ -14,28 +14,6 @@
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "4"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
......
{
"comment": "Any Firmware, Multi Rotor",
"version": 1,
"fileType": "MavCmdInfo",
"comment": "Any Firmware, Multi Rotor",
"version": 1,
"fileType": "MavCmdInfo",
"mavCmdInfo": [
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "3"
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"paramRemove": "2,3,4"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "1"
},
{
"id": 31,
"comment": "MAV_CMD_NAV_LOITER_TO_ALT",
"paramRemove": "1,2,4"
}
]
}
/****************************************************************************
*
* (c) 2009-2020 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 "MissionCommandTreeEditorTest.h"
#include "QGCApplication.h"
#include "QGCCorePlugin.h"
#include "SimpleMissionItem.h"
#include "PlanMasterController.h"
MissionCommandTreeEditorTest::MissionCommandTreeEditorTest(void)
{
}
void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_t firmwareClass, QGCMAVLink::VehicleClass_t vehicleClass)
{
QString firmwareClassString = QGCMAVLink::firmwareClassToString(firmwareClass).replace(" ", "");
QString vehicleClassString = QGCMAVLink::vehicleClassToString(vehicleClass).replace(" ", "");
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
appSettings->offlineEditingFirmwareClass()->setRawValue(firmwareClass);
appSettings->offlineEditingVehicleClass()->setRawValue(vehicleClass);
PlanMasterController* masterController = new PlanMasterController();
FirmwarePlugin* firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(firmwareClass), QGCMAVLink::vehicleClassToMavType(vehicleClass));
if (firmwarePlugin->supportedMissionCommands().count() == 0) {
firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(QGCMAVLink::FirmwareClassPX4), QGCMAVLink::vehicleClassToMavType(vehicleClass));
}
int cColumns = firmwarePlugin->supportedMissionCommands().count();
QVariantList varSimpleItems;
for (MAV_CMD command: firmwarePlugin->supportedMissionCommands()) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(masterController, false /* flyView */, false /* forLoad */, this);
simpleItem->setCommand(command);
varSimpleItems.append(QVariant::fromValue(simpleItem));
}
QQmlApplicationEngine* qmlAppEngine = qgcApp()->toolbox()->corePlugin()->createQmlApplicationEngine(this);
qmlAppEngine->rootContext()->setContextProperty("planMasterController", masterController);
qmlAppEngine->rootContext()->setContextProperty("missionItems", varSimpleItems);
qmlAppEngine->rootContext()->setContextProperty("cColumns", cColumns);
qmlAppEngine->rootContext()->setContextProperty("imagePath", QStringLiteral("/home/parallels/Downloads/%1-%2.png").arg(firmwareClassString).arg(vehicleClassString));
qmlAppEngine->load(QUrl(QStringLiteral("qrc:/qml/MissionCommandTreeEditorTestWindow.qml")));
QTest::qWait(1000);
delete qmlAppEngine;
}
void MissionCommandTreeEditorTest::testEditors(void)
{
for (const QGCMAVLink::FirmwareClass_t& firmwareClass: QGCMAVLink::allFirmwareClasses()) {
for (const QGCMAVLink::VehicleClass_t& vehicleClass: QGCMAVLink::allVehicleClasses()) {
_testEditorsWorker(firmwareClass, vehicleClass);
}
}
}
/****************************************************************************
*
* (c) 2009-2020 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.
*
****************************************************************************/
#pragma once
#include "UnitTest.h"
/// This unit test is meant to be used stand-alone to generate images for each mission item editor for review
class MissionCommandTreeEditorTest : public UnitTest
{
Q_OBJECT
public:
MissionCommandTreeEditorTest(void);
private slots:
void testEditors(void);
private:
void _testEditorsWorker(QGCMAVLink::FirmwareClass_t firmwareClass, QGCMAVLink::VehicleClass_t vehicleClass);
};
/****************************************************************************
*
* (c) 2009-2020 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.
*
****************************************************************************/
import QtQuick 2.12
import QtQuick.Controls 2.4
import QtQuick.Dialogs 1.3
import QtQuick.Layouts 1.11
import QtQuick.Window 2.11
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.Controllers 1.0
ApplicationWindow {
id: _root
visible: true
visibility: Qt.WindowFullScreen
color: qgcPal.window
property real editorWidth: ScreenTools.defaultFontPixelWidth * 30
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Timer {
id: timer
interval: 100
onTriggered: {
var success = fullImage.grabToImage(function(result) { result.saveToFile(imagePath) })
console.log(success)
}
}
Component.onCompleted: timer.start()
Flow {
id: fullImage
anchors.fill: parent
Repeater {
model: missionItems
Column {
QGCLabel { text: modelData.commandName; color: "black" }
Loader {
id: editorLoader
source: modelData.editorQml
property var missionItem: modelData
property var masterController: planMasterController
property real availableWidth: editorWidth
}
}
}
}
}
......@@ -38,8 +38,8 @@ const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoi
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesLoiterTime[] = {
{ "Radius", 30.1234567 },
{ "Hold", 10.1234567 },
{ "Radius", 30.1234567 },
{ "Loiter Time", 10.1234567 },
};
const SimpleMissionItemTest::FactValue_t SimpleMissionItemTest::_rgFactValuesTakeoff[] = {
......@@ -57,7 +57,7 @@ const SimpleMissionItemTest::ItemExpected_t SimpleMissionItemTest::_rgItemExpect
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterUnlim[0]), SimpleMissionItemTest::_rgFactValuesLoiterUnlim, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTurns[0]), SimpleMissionItemTest::_rgFactValuesLoiterTurns, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime)/sizeof(SimpleMissionItemTest::_rgFactValuesLoiterTime[0]), SimpleMissionItemTest::_rgFactValuesLoiterTime, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ 0, nullptr, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ 0, nullptr, 70.1234567, QGroundControlQmlGlobal::AltitudeModeRelative },
{ sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff)/sizeof(SimpleMissionItemTest::_rgFactValuesTakeoff[0]), SimpleMissionItemTest::_rgFactValuesTakeoff, 70.1234567, QGroundControlQmlGlobal::AltitudeModeAbsolute },
{ sizeof(SimpleMissionItemTest::_rgFactValuesDoJump)/sizeof(SimpleMissionItemTest::_rgFactValuesDoJump[0]), SimpleMissionItemTest::_rgFactValuesDoJump, qQNaN(), QGroundControlQmlGlobal::AltitudeModeRelative },
};
......
......@@ -23,6 +23,7 @@ Rectangle {
property bool _supportsTerrainFrame: _controllerVehicle.supportsTerrainFrame
property int _globalAltMode: missionItem.masterController.missionController.globalAltitudeMode
property bool _globalAltModeIsMixed: _globalAltMode == QGroundControl.AltitudeModeNone
property real _radius: ScreenTools.defaultFontPixelWidth / 2
property string _altModeRelativeHelpText: qsTr("Altitude relative to launch altitude")
property string _altModeAbsoluteHelpText: qsTr("Altitude above mean sea level")
......@@ -55,6 +56,8 @@ Rectangle {
onAltitudeModeChanged: updateAltitudeModeText()
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
Column {
id: editorColumn
anchors.margins: _margin
......@@ -120,37 +123,6 @@ Rectangle {
spacing: _margin
visible: !missionItem.wizardMode
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columns: 2
Repeater {
model: missionItem.comboboxFacts
QGCLabel {
text: object.name
visible: object.name !== ""
Layout.column: 0
Layout.row: index
}
}
Repeater {
model: missionItem.comboboxFacts
FactComboBox {
indexModel: false
model: object.enumStrings
fact: object
font.pointSize: ScreenTools.smallFontPointSize
Layout.column: 1
Layout.row: index
Layout.fillWidth: true
}
}
}
// This control needs to morph between a simple altitude entry field to a more complex alt mode picker based on the global plan alt mode
Rectangle {
anchors.left: parent.left
......@@ -258,6 +230,34 @@ Rectangle {
}
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
Repeater {
model: missionItem.comboboxFacts
ColumnLayout {
Layout.fillWidth: true
spacing: 0
QGCLabel {
font.pointSize: ScreenTools.smallFontPointSize
text: object.name
visible: object.name !== ""
}
FactComboBox {
Layout.fillWidth: true
indexModel: false
model: object.enumStrings
fact: object
}
}
}
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
......
......@@ -590,18 +590,18 @@ void QGCApplication::_initCommon()
qmlRegisterSingletonType<QGroundControlQmlGlobal> ("QGroundControl", 1, 0, "QGroundControl", qgroundcontrolQmlGlobalSingletonFactory);
qmlRegisterSingletonType<ScreenToolsController> ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
qmlRegisterSingletonType<ShapeFileHelper> ("QGroundControl.ShapeFileHelper", 1, 0, "ShapeFileHelper", shapeFileHelperSingletonFactory);
}
bool QGCApplication::_initForNormalAppBoot()
{
// Although this should really be in _initForNormalAppBoot putting it here allowws us to create unit tests which pop up more easily
if(QFontDatabase::addApplicationFont(":/fonts/opensans") < 0) {
qWarning() << "Could not load /fonts/opensans font";
}
if(QFontDatabase::addApplicationFont(":/fonts/opensans-demibold") < 0) {
qWarning() << "Could not load /fonts/opensans-demibold font";
}
}
bool QGCApplication::_initForNormalAppBoot()
{
QSettings settings;
_qmlAppEngine = toolbox()->corePlugin()->createQmlApplicationEngine(this);
......
......@@ -9,6 +9,8 @@
#include "QGCMAVLink.h"
#include <QtGlobal>
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassPX4;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassArduPilot;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassGeneric;
......@@ -56,6 +58,20 @@ QGCMAVLink::FirmwareClass_t QGCMAVLink::firmwareClass(MAV_AUTOPILOT autopilot)
}
}
QString QGCMAVLink::firmwareClassToString(FirmwareClass_t firmwareClass)
{
switch (firmwareClass) {
case FirmwareClassPX4:
return QT_TRANSLATE_NOOP("Firmware Class", "PX4 Pro");
case FirmwareClassArduPilot:
return QT_TRANSLATE_NOOP("Firmware Class", "ArduPilot");
case FirmwareClassGeneric:
return QT_TRANSLATE_NOOP("Firmware Class", "Generic");
default:
return QT_TRANSLATE_NOOP("Firmware Class", "Unknown");
}
}
bool QGCMAVLink::isFixedWing(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassFixedWing;
......@@ -109,6 +125,26 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType)
}
}
QString QGCMAVLink::vehicleClassToString(VehicleClass_t vehicleClass)
{
switch (vehicleClass) {
case VehicleClassFixedWing:
return QT_TRANSLATE_NOOP("Vehicle Class", "Fixed Wing");
case VehicleClassRoverBoat:
return QT_TRANSLATE_NOOP("Vehicle Class", "Rover-Boat");
case VehicleClassSub:
return QT_TRANSLATE_NOOP("Vehicle Class", "Sub");
case VehicleClassMultiRotor:
return QT_TRANSLATE_NOOP("Vehicle Class", "Multi-Rotor");
case VehicleClassVTOL:
return QT_TRANSLATE_NOOP("Vehicle Class", "VTOL");
case VehicleClassGeneric:
return QT_TRANSLATE_NOOP("Vehicle Class", "Generic");
default:
return QT_TRANSLATE_NOOP("Vehicle Class", "Unknown");
}
}
QString QGCMAVLink::mavResultToString(MAV_RESULT result)
{
switch (result) {
......
......@@ -68,6 +68,7 @@ public:
static bool isGenericFirmwareClass (MAV_AUTOPILOT autopilot) { return !isPX4FirmwareClass(autopilot) && ! isArduPilotFirmwareClass(autopilot); }
static FirmwareClass_t firmwareClass (MAV_AUTOPILOT autopilot);
static MAV_AUTOPILOT firmwareClassToAutopilot(FirmwareClass_t firmwareClass) { return static_cast<MAV_AUTOPILOT>(firmwareClass); }
static QString firmwareClassToString (FirmwareClass_t firmwareClass);
static QList<FirmwareClass_t> allFirmwareClasses (void);
static bool isFixedWing (MAV_TYPE mavType);
......@@ -77,9 +78,10 @@ public:
static bool isVTOL (MAV_TYPE mavType);
static VehicleClass_t vehicleClass (MAV_TYPE mavType);
static MAV_TYPE vehicleClassToMavType (VehicleClass_t vehicleClass) { return static_cast<MAV_TYPE>(vehicleClass); }
static QString vehicleClassToString (VehicleClass_t vehicleClass);
static QList<VehicleClass_t> allVehicleClasses (void);
static QString mavResultToString (MAV_RESULT result);
static QString mavResultToString (MAV_RESULT result);
};
class MavlinkFTP {
......
......@@ -37,15 +37,6 @@ enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileNam
int UnitTest::_missedFileDialogCount = 0;
UnitTest::UnitTest(void)
: _linkManager (nullptr)
, _mockLink (nullptr)
, _mainWindow (nullptr)
, _vehicle (nullptr)
, _expectMissedFileDialog (false)
, _expectMissedMessageBox (false)
, _unitTestRun (false)
, _initCalled (false)
, _cleanupCalled (false)
{
}
......@@ -59,9 +50,9 @@ UnitTest::~UnitTest()
}
}
void UnitTest::_addTest(QObject* test)
void UnitTest::_addTest(UnitTest* test)
{
QList<QObject*>& tests = _testList();
QList<UnitTest*>& tests = _testList();
Q_ASSERT(!tests.contains(test));
......@@ -74,9 +65,9 @@ void UnitTest::_unitTestCalled(void)
}
/// @brief Returns the list of unit tests.
QList<QObject*>& UnitTest::_testList(void)
QList<UnitTest*>& UnitTest::_testList(void)
{
static QList<QObject*> tests;
static QList<UnitTest*> tests;
return tests;
}
......@@ -84,8 +75,11 @@ int UnitTest::run(QString& singleTest)
{
int ret = 0;
for (QObject* test: _testList()) {
for (UnitTest* test: _testList()) {
if (singleTest.isEmpty() || singleTest == test->objectName()) {
if (test->standalone() && singleTest.isEmpty()) {
continue;
}
QStringList args;
args << "*" << "-maxwarnings" << "0";
ret += QTest::qExec(test, args);
......@@ -136,7 +130,6 @@ void UnitTest::cleanup(void)
_cleanupCalled = true;
_disconnectMockLink();
_closeMainWindow();
// Keep in mind that any code below these QCOMPARE may be skipped if the compare fails
if (_expectMissedMessageBox) {
......@@ -433,36 +426,6 @@ void UnitTest::_linkDeleted(LinkInterface* link)
}
}
void UnitTest::_createMainWindow(void)
{
//-- TODO
#if 0
_mainWindow = MainWindow::_create();
Q_CHECK_PTR(_mainWindow);
#endif
}
void UnitTest::_closeMainWindow(bool cancelExpected)
{
//-- TODO
#if 0
if (_mainWindow) {
QSignalSpy mainWindowSpy(_mainWindow, SIGNAL(mainWindowClosed()));
_mainWindow->close();
mainWindowSpy.wait(2000);
QCOMPARE(mainWindowSpy.count(), cancelExpected ? 0 : 1);
// This leaves enough time for any dangling Qml components to get cleaned up.
// This prevents qWarning from bad references in Qml
QTest::qWait(1000);
}
#else
Q_UNUSED(cancelExpected);
#endif
}
QString UnitTest::createRandomFile(uint32_t byteCount)
{
QTemporaryFile tempFile;
......
......@@ -26,13 +26,13 @@
#include "Fact.h"
#include "MissionItem.h"
#define UT_REGISTER_TEST(className) static UnitTestWrapper<className> className(#className);
#define UT_REGISTER_TEST(className) static UnitTestWrapper<className> className(#className, false);
#define UT_REGISTER_TEST_STANDALONE(className) static UnitTestWrapper<className> className(#className, true);
class QGCMessageBox;
class QGCQFileDialog;
class LinkManager;
class MockLink;
class MainWindow;
class Vehicle;
class UnitTest : public QObject
......@@ -82,8 +82,11 @@ public:
// @param Expected failure response flags
void checkExpectedFileDialog(int expectFailFlags = expectFailNoFailure);
bool standalone(void) { return _standalone; }
void setStandalone(bool standalone) { _standalone = standalone; }
/// @brief Adds a unit test to the list. Should only be called by UnitTestWrapper.
static void _addTest(QObject* test);
static void _addTest(UnitTest* test);
/// Creates a file with random contents of the specified size.
/// @return Fully qualified path to created file
......@@ -122,17 +125,14 @@ protected:
void _connectMockLink(MAV_AUTOPILOT autopilot = MAV_AUTOPILOT_PX4);
void _connectMockLinkNoInitialConnectSequence(void) { _connectMockLink(MAV_AUTOPILOT_INVALID); }
void _disconnectMockLink(void);
void _createMainWindow(void);
void _closeMainWindow(bool cancelExpected = false);
void _missionItemsEqual(MissionItem& actual, MissionItem& expected);
LinkManager* _linkManager;
MockLink* _mockLink;
MainWindow* _mainWindow;
Vehicle* _vehicle;
LinkManager* _linkManager = nullptr;
MockLink* _mockLink = nullptr;
Vehicle* _vehicle = nullptr;
bool _expectMissedFileDialog; // true: expect a missed file dialog, used for internal testing
bool _expectMissedMessageBox; // true: expect a missed message box, used for internal testing
bool _expectMissedFileDialog = false; // true: expect a missed file dialog, used for internal testing
bool _expectMissedMessageBox = false; // true: expect a missed message box, used for internal testing
private slots:
void _linkDeleted(LinkInterface* link);
......@@ -185,7 +185,7 @@ private:
friend class QGCQFileDialog;
void _unitTestCalled(void);
static QList<QObject*>& _testList(void);
static QList<UnitTest*>& _testList(void);
// Catch QGCMessageBox calls
static bool _messageBoxRespondedTo; ///< Message box was responded to
......@@ -200,18 +200,20 @@ private:
static enum FileDialogType _fileDialogExpectedType; ///< type of file dialog expected to show
static int _missedFileDialogCount; ///< Count of file dialogs not checked with call to UnitTest::fileDialogWasDisplayed
bool _unitTestRun; ///< true: Unit Test was run
bool _initCalled; ///< true: UnitTest::_init was called
bool _cleanupCalled; ///< true: UnitTest::_cleanup was called
bool _unitTestRun = false; ///< true: Unit Test was run
bool _initCalled = false; ///< true: UnitTest::_init was called
bool _cleanupCalled = false; ///< true: UnitTest::_cleanup was called
bool _standalone = false; ///< true: Only run when requested specifically from command line
};
template <class T>
class UnitTestWrapper {
public:
UnitTestWrapper(const QString& name) :
_unitTest(new T)
UnitTestWrapper(const QString& name, bool standalone)
: _unitTest(new T)
{
_unitTest->setObjectName(name);
_unitTest->setStandalone(standalone);
UnitTest::_addTest(_unitTest.data());
}
......
......@@ -48,6 +48,7 @@
#include "RequestMessageTest.h"
#include "InitialConnectTest.h"
#include "FTPManagerTest.h"
#include "MissionCommandTreeEditorTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -83,6 +84,7 @@ UT_REGISTER_TEST(TransectStyleComplexItemTest)
UT_REGISTER_TEST(QGCMapPolylineTest)
UT_REGISTER_TEST(CameraCalcTest)
UT_REGISTER_TEST(FWLandingPatternTest)
UT_REGISTER_TEST_STANDALONE(MissionCommandTreeEditorTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
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