Commit 0cecf13f authored by Don Gagne's avatar Don Gagne

Major rewrite of Mission Item json editor support

parent 4335dbad
<RCC>
<qresource prefix="/json/unittest">
<file alias="MavCmdInfoCommon.json">src/MissionManager/UnitTest/MavCmdInfoCommon.json</file>
<file alias="MavCmdInfoFixedWing.json">src/MissionManager/UnitTest/MavCmdInfoFixedWing.json</file>
<file alias="MavCmdInfoMultiRotor.json">src/MissionManager/UnitTest/MavCmdInfoMultiRotor.json</file>
<file alias="MavCmdInfoRover.json">src/MissionManager/UnitTest/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/UnitTest/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/UnitTest/MavCmdInfoVTOL.json</file>
</qresource>
</RCC>
......@@ -178,6 +178,11 @@ RESOURCES += \
qgroundcontrol.qrc \
qgcresources.qrc
DebugBuild {
# Unit Test resources
RESOURCES += UnitTest.qrc
}
DEPENDPATH += \
. \
plugins
......@@ -268,7 +273,8 @@ HEADERS += \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommands.h \
src/MissionManager/MissionCommandTree.h \
src/MissionManager/MissionCommandUIInfo.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
......@@ -412,6 +418,7 @@ SOURCES += \
src/comm/LinkConfiguration.cc \
src/comm/LinkManager.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/QGCMAVLink.cc \
src/comm/TCPLink.cc \
src/comm/UDPLink.cc \
src/FlightDisplay/FlightDisplayViewController.cc \
......@@ -427,7 +434,8 @@ SOURCES += \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionCommandTree.cc \
src/MissionManager/MissionCommandUIInfo.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
......@@ -554,6 +562,7 @@ HEADERS += \
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/MissionManager/ComplexMissionItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \
......@@ -580,6 +589,7 @@ SOURCES += \
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/MissionManager/ComplexMissionItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \
......
......@@ -163,12 +163,23 @@
</qresource>
<qresource prefix="/json">
<file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.json</file>
<file alias="MavCmdInfoFixedWing.json">src/MissionManager/MavCmdInfoFixedWing.json</file>
<file alias="MavCmdInfoMultiRotor.json">src/MissionManager/MavCmdInfoMultiRotor.json</file>
<file alias="MavCmdInfoRover.json">src/MissionManager/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/MavCmdInfoVTOL.json</file>
<file alias="APM/MavCmdInfoCommon.json">src/FirmwarePlugin/APM/MavCmdInfoCommon.json</file>
<file alias="APM/MavCmdInfoFixedWing.json">src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json</file>
<file alias="APM/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json</file>
<file alias="APM/MavCmdInfoRover.json">src/FirmwarePlugin/APM/MavCmdInfoRover.json</file>
<file alias="APM/MavCmdInfoSub.json">src/FirmwarePlugin/APM/MavCmdInfoSub.json</file>
<file alias="APM/MavCmdInfoVTOL.json">src/FirmwarePlugin/APM/MavCmdInfoVTOL.json</file>
<file alias="PX4/MavCmdInfoCommon.json">src/FirmwarePlugin/PX4/MavCmdInfoCommon.json</file>
<file alias="PX4/MavCmdInfoFixedWing.json">src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json</file>
<file alias="PX4/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json</file>
<file alias="PX4/MavCmdInfoRover.json">src/FirmwarePlugin/PX4/MavCmdInfoRover.json</file>
<file alias="PX4/MavCmdInfoSub.json">src/FirmwarePlugin/PX4/MavCmdInfoSub.json</file>
<file alias="PX4/MavCmdInfoVTOL.json">src/FirmwarePlugin/PX4/MavCmdInfoVTOL.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
......
......@@ -576,30 +576,66 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
list << MAV_CMD_NAV_WAYPOINT << MAV_CMD_NAV_SPLINE_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME
<< MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
<< MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT
<< MAV_CMD_NAV_LOITER_TO_ALT
<< MAV_CMD_NAV_SPLINE_WAYPOINT
<< MAV_CMD_NAV_GUIDED_ENABLE
<< MAV_CMD_DO_SET_ROI << MAV_CMD_DO_GUIDED_LIMITS << MAV_CMD_DO_JUMP << MAV_CMD_DO_CHANGE_SPEED << MAV_CMD_DO_SET_CAM_TRIGG_DIST
<< MAV_CMD_NAV_DELAY
<< MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW
<< MAV_CMD_DO_SET_MODE
<< MAV_CMD_DO_JUMP
<< MAV_CMD_DO_CHANGE_SPEED
<< MAV_CMD_DO_SET_HOME
<< MAV_CMD_DO_SET_RELAY << MAV_CMD_DO_REPEAT_RELAY
<< MAV_CMD_DO_SET_SERVO << MAV_CMD_DO_REPEAT_SERVO
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_SET_ROI
<< MAV_CMD_DO_DIGICAM_CONFIGURE << MAV_CMD_DO_DIGICAM_CONTROL
<< MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_DO_SET_HOME
<< MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_FENCE_ENABLE << MAV_CMD_DO_PARACHUTE << MAV_CMD_DO_INVERTED_FLIGHT << MAV_CMD_DO_GRIPPER
<< MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_CHANGE_ALT << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW
<< MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
<< MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT;
<< MAV_CMD_DO_SET_CAM_TRIGG_DIST
<< MAV_CMD_DO_FENCE_ENABLE
<< MAV_CMD_DO_PARACHUTE
<< MAV_CMD_DO_INVERTED_FLIGHT
<< MAV_CMD_DO_GRIPPER
<< MAV_CMD_DO_GUIDED_LIMITS
<< MAV_CMD_DO_AUTOTUNE_ENABLE
<< MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND << MAV_CMD_DO_VTOL_TRANSITION;
#if 0
// Waiting for module update
<< MAV_CMD_DO_SET_REVERSE;
#endif
return list;
}
void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
{
commonJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoCommon.json");
fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
switch (vehicleType) {
case MAV_TYPE_GENERIC:
return QStringLiteral(":/json/APM/MavCmdInfoCommon.json");
break;
case MAV_TYPE_FIXED_WING:
return QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
break;
case MAV_TYPE_QUADROTOR:
return QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
break;
case MAV_TYPE_VTOL_QUADROTOR:
return QStringLiteral(":/json/APM/MavCmdInfoVTOL.json");
break;
case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/json/APM/MavCmdInfoSub.json");
break;
case MAV_TYPE_GROUND_ROVER:
return QStringLiteral(":/json/APM/MavCmdInfoRover.json");
break;
default:
qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
return QString();
}
}
QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
......
......@@ -73,21 +73,21 @@ public:
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QList<MAV_CMD> supportedMissionCommands(void) final;
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities);
QStringList flightModes(Vehicle* vehicle) final;
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
bool isGuidedMode(const Vehicle* vehicle) const final;
void pauseVehicle(Vehicle* vehicle);
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities);
QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
bool isGuidedMode (const Vehicle* vehicle) const final;
void pauseVehicle (Vehicle* vehicle);
int manualControlReservedButtonCount(void);
bool adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
void adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
void initializeVehicle(Vehicle* vehicle) final;
bool sendHomePositionToVehicle(void) final;
void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam(void) const final { return QString("SYSID_SW_TYPE"); }
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
QString getVersionParam(void) final { return QStringLiteral("SYSID_SW_MREV"); }
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYSID_SW_TYPE"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const;
QString getVersionParam (void) final { return QStringLiteral("SYSID_SW_MREV"); }
QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/APM/APMParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
......
{
"comment": "ArduPilot, Any Vehicle",
"version": 1,
"mavCmdInfo": [
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground.",
"specifiesCoordinate": false,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Pitch:",
"units": "deg",
"default": 15,
"decimalPlaces": 2
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 25.0,
"decimalPlaces": 2
}
},
{
"id": 84,
"rawName": "MAV_CMD_NAV_VTOL_TAKEOFF",
"friendlyName": "VTOL takeoff",
"description": "Takeoff from ground using VTOL mode.",
"comment": "MAV_CMD_NAV_VTOL_TAKEOFF",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "VTOL"
},
{
"id": 85,
"rawName": "MAV_CMD_NAV_VTOL_LAND",
"friendlyName": "VTOL land",
"comment": "MAV_CMD_NAV_VTOL_LAND",
"description": "Land using VTOL mode.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "VTOL",
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0.0,
"category": "VTOL"
},
{
"id": 176,
"comment": "MAV_CMD_DO_SET_MODE",
"paramRemove": "2,3"
},
{
"id": 178,
"comment": "MAV_CMD_DO_CHANGE_SPEED",
"paramRemove": "4"
},
{
"id": 181,
"comment": "MAV_CMD_DO_SET_RELAY",
"param2": {
"label": "Setting:",
"enumStrings": "On,Off",
"enumValues": "1,0",
"default": 1
}
},
{
"id": 201,
"comment": "MAV_CMD_DO_SET_ROI",
"paramRemove": "2,3"
},
{
"id": 205,
"comment": "MAV_CMD_DO_MOUNT_CONTROL",
"paramRemove": "7",
"param1": {
"label": "Pitch:",
"default": 0,
"units": "deg",
"decimalPlaces": 2
},
"param2": {
"label": "Roll:",
"default": 0,
"units": "deg",
"decimalPlaces": 2
},
"param3": {
"label": "Yaw:",
"default": 0,
"units": "deg",
"decimalPlaces": 2
}
},
{
"id": 207,
"comment": "MAV_CMD_DO_FENCE_ENABLE",
"param1": {
"label": "Enable:",
"enumStrings": "Enable,Disable",
"enumValues": "1,0",
"default": 1
}
}
]
}
{
"comment": "ArduPilot, Fixed Wing",
"version": 1,
"mavCmdInfo": [
{
"id": 16,
"rawName": "MAV_CMD_NAV_WAYPOINT",
"friendlyName": "Waypoint",
"description": "Travel to a position in 3D space.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "secs",
"default": 0,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "1,3,4"
},
{
"id": 17,
"rawName": "MAV_CMD_NAV_LOITER_UNLIM",
"friendlyName": "Loiter",
"description": "Travel to a position and Loiter around the specified radius indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "4"
},
{
"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.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Turns:",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,
"paramRemove": "2,3,4,5,6"
},
{
"id": 19,
"rawName": "MAV_CMD_NAV_LOITER_TIME",
"friendlyName": "Loiter (time)",
"description": "Travel to a position and Loiter around the specified radius for a number of seconds.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Seconds:",
"units": "secs",
"default": 30,
"decimalPlaces": 1
},
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
},
{
"id": 21,
"rawName": "MAV_CMD_NAV_LAND",
"friendlyName": "Land",
"description": "Land vehicle at the specified location.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Abort Alt:",
"units": "m",
"default": 25,
"decimalPlaces": 0
},
"param4": {
"label": "Heading:",
"units": "radians",
"default": 0,
"decimalPlaces": 2
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0,
"decimalPlaces": 1
}
},
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground and travel towards the specified position.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Pitch:",
"units": "deg",
"default": 10,
"decimalPlaces": 0
},
"param4": {
"label": "Heading:",
"units": "radians",
"default": 0,
"decimalPlaces": 1
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 25,
"decimalPlaces": 0
}
},
{
"id": 31,
"rawName": "MAV_CMD_NAV_LOITER_TO_ALT",
"friendlyName": "Loiter (altitude)",
"description": "Travel to a position and Loiter around the specified radius until the given altitude.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Heading wait:",
"enumStrings": "False,True",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param2": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
},
{
"id": 206,
"rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST",
"friendlyName": "Camera trigger distance",
"description": "Set camera trigger distance.",
"category": "Camera",
"param1": {
"label": "Distance:",
"default": 25,
"units": "m",
"decimalPlaces": 1
}
"id": 82,
"comment": "MAV_CMD_NAV_SPLINE_WAYPOINT",
"paramRemove": "1"
}
]
}
{
"comment": "ArduPilot, Multi Rotor",
"version": 1,
"mavCmdInfo": [
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground.",
"specifiesCoordinate": false,
"friendlyEdit": true,
"category": "Basic",
"param7": {
"label": "Altitude:",
"units": "m",
"default": 25.0,
"decimalPlaces": 2
}
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2,3,4"
},
{
"id": 17,
"rawName": "MAV_CMD_NAV_LOITER_UNLIM",
"friendlyName": "Loiter",
"description": "Travel to a position and Loiter indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic"
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "3"
},
{
"id": 18,
"rawName": "MAV_CMD_NAV_LOITER_TURNS",
"friendlyName": "Loiter (turns)",
"description": "Travel to a position and Circle with the specified radius for a number of turns.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Turns:",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Radius:",
"units": "m",
"default": 10.0,
"decimalPlaces": 2
}
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"paramRemove": "4"
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"paramRemove": "4"
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1,4"
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"specifiesCoordinate": false,
"paramRemove": "1,2,3,4,5,6"
},
{
"id": 19,
"rawName": "MAV_CMD_NAV_LOITER_TIME",
"friendlyName": "Loiter (time)",
"description": "Travel to a position and Loiter for an amount of time.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "secs",
"default": 30,
"decimalPlaces": 0
}
"id": 31,
"comment": "MAV_CMD_NAV_LOITER_TO_ALT",
"paramRemove": "4"
}
]
}
{
"comment": "ArduPilot, Rover",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "ArduPilot, Sub",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "ArduPilot, VTOL",
"version": 1,
"mavCmdInfo": [
]
}
......@@ -38,12 +38,12 @@ QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) cons
const char* name;
};
static const struct Bit2Name rgBit2Name[] = {
{ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, "Manual" },
{ MAV_MODE_FLAG_STABILIZE_ENABLED, "Stabilize" },
{ MAV_MODE_FLAG_GUIDED_ENABLED, "Guided" },
{ MAV_MODE_FLAG_AUTO_ENABLED, "Auto" },
{ MAV_MODE_FLAG_TEST_ENABLED, "Test" },
};
{ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, "Manual" },
{ MAV_MODE_FLAG_STABILIZE_ENABLED, "Stabilize" },
{ MAV_MODE_FLAG_GUIDED_ENABLED, "Guided" },
{ MAV_MODE_FLAG_AUTO_ENABLED, "Auto" },
{ MAV_MODE_FLAG_TEST_ENABLED, "Test" },
};
Q_UNUSED(custom_mode);
......@@ -140,12 +140,31 @@ QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
return QList<MAV_CMD>();
}
void FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
{
// No overrides
commonJsonFilename.clear();
fixedWingJsonFilename.clear();
multiRotorJsonFilename.clear();
switch (vehicleType) {
case MAV_TYPE_GENERIC:
return QStringLiteral(":/json/MavCmdInfoCommon.json");
break;
case MAV_TYPE_FIXED_WING:
return QStringLiteral(":/json/MavCmdInfoFixedWing.json");
break;
case MAV_TYPE_QUADROTOR:
return QStringLiteral(":/json/MavCmdInfoMultiRotor.json");
break;
case MAV_TYPE_VTOL_QUADROTOR:
return QStringLiteral(":/json/MavCmdInfoVTOL.json");
break;
case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/json/MavCmdInfoSub.json");
break;
case MAV_TYPE_GROUND_ROVER:
return QStringLiteral(":/json/MavCmdInfoRover.json");
break;
default:
qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
return QString();
}
}
void FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
......
......@@ -192,11 +192,9 @@ public:
/// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void);
/// Returns the names for the mission command json override files. Empty string to specify no overrides.
/// @param[out] commonJsonFilename Filename for common overrides
/// @param[out] fixedWingJsonFilename Filename for fixed wing overrides
/// @param[out] multiRotorJsonFilename Filename for multi rotor overrides
virtual void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const;
/// Returns the name of the mission command json override file for the specified vehicle type.
/// @param vehicleType Vehicle type to return file for, MAV_TYPE_GENERIC is a request for overrides for all vehicle types
virtual QString missionCommandOverrides(MAV_TYPE vehicleType) const;
/// Returns the mapping structure which is used to map from one parameter name to another based on firmware version.
virtual const remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const;
......
......@@ -40,6 +40,13 @@ FirmwarePluginManager::~FirmwarePluginManager()
delete _px4FirmwarePlugin;
}
QList<MAV_AUTOPILOT> FirmwarePluginManager::knownFirmwareTypes(void) const
{
QList<MAV_AUTOPILOT> list;
list << MAV_AUTOPILOT_GENERIC << MAV_AUTOPILOT_PX4 << MAV_AUTOPILOT_ARDUPILOTMEGA;
return list;
}
FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType)
{
switch (autopilotType) {
......
......@@ -37,6 +37,8 @@ public:
FirmwarePluginManager(QGCApplication* app);
~FirmwarePluginManager();
QList<MAV_AUTOPILOT> knownFirmwareTypes(void) const;
/// Returns appropriate plugin for autopilot type.
/// @param autopilotType Type of autopilot to return plugin for.
/// @param vehicleType Vehicle type of autopilot to return plugin for.
......
{
"comment": "PX4 Pro, Any Vehicle",
"version": 1,
"mavCmdInfo": [
......
{
"comment": "PX4 Pro, Fixed Wing",
"version": 1,
"mavCmdInfo": [
{
"id": 16,
"rawName": "MAV_CMD_NAV_WAYPOINT",
"friendlyName": "Waypoint",
"description": "Travel to a position in 3D space.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "secs",
"default": 0,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "3,4"
},
{
"id": 17,
"rawName": "MAV_CMD_NAV_LOITER_UNLIM",
"friendlyName": "Loiter",
"description": "Travel to a position and Loiter around the specified radius indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
"paramRemove": "1,4"
},
{
"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.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Turns:",
"default": 1,
"decimalPlaces": 0
},
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"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 a number of seconds.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Seconds:",
"units": "secs",
"default": 30,
"decimalPlaces": 1
},
"param3": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
},
{
"id": 21,
"rawName": "MAV_CMD_NAV_LAND",
"friendlyName": "Land",
"description": "Land vehicle at the specified location.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0,
"decimalPlaces": 1
}
},
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground and travel towards the specified position.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Pitch:",
"units": "deg",
"default": 10,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 25,
"decimalPlaces": 0
}
},
{
"id": 31,
"rawName": "MAV_CMD_NAV_LOITER_TO_ALT",
"friendlyName": "Loiter (altitude)",
"description": "Travel to a position and Loiter around the specified radius until the given altitude.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Loiter",
"param1": {
"label": "Heading wait:",
"enumStrings": "False,True",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param2": {
"label": "Radius:",
"units": "m",
"default": 50,
"decimalPlaces": 0
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 50,
"decimalPlaces": 0
}
},
{
"id": 206,
"rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST",
"friendlyName": "Camera trigger distance",
"description": "Set camera trigger distance.",
"category": "Camera",
"param1": {
"label": "Distance:",
"default": 25,
"units": "m",
"decimalPlaces": 1
}
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
"paramRemove": "4"
}
]
}
{
"comment": "PX4 Pro, Multi Rotor",
"version": 1,
"mavCmdInfo": [
{
"id": 17,
"rawName": "MAV_CMD_NAV_LOITER_UNLIM",
"friendlyName": "Loiter",
"description": "Travel to a position and Loiter indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic"
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"description": "Travel to a position and Loiter indefinitely.",
"paramRemove": "3"
},
{
"id": 18,
"rawName": "MAV_CMD_NAV_LOITER_TURNS",
"friendlyName": "Loiter (turns)",
"description": "Travel to a position and Loiter for a number of turns.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Turns:",
"default": 1,
"decimalPlaces": 0
}
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"description": "Travel to a position and Loiter for a number of turns.",
"paramRemove": "3,4"
},
{
"id": 19,
"rawName": "MAV_CMD_NAV_LOITER_TIME",
"friendlyName": "Loiter (time)",
"description": "Travel to a position and Loiter for an amount of time.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "secs",
"default": 30,
"decimalPlaces": 0
}
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"description": "Travel to a position and Loiter for an amount of time.",
"paramRemove": "3,4"
}
]
}
{
"comment": "PX4 Pro, Rover",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "PX4 Pro, Sub",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "PX4 Pro, VTOL",
"version": 1,
"mavCmdInfo": [
]
}
......@@ -228,12 +228,31 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
return list;
}
void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
{
// No overrides
commonJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoCommon.json");
fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
switch (vehicleType) {
case MAV_TYPE_GENERIC:
return QStringLiteral(":/json/PX4/MavCmdInfoCommon.json");
break;
case MAV_TYPE_FIXED_WING:
return QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
break;
case MAV_TYPE_QUADROTOR:
return QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
break;
case MAV_TYPE_VTOL_QUADROTOR:
return QStringLiteral(":/json/APM/MavCmdInfoVTOL.json");
break;
case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/json/PX4/MavCmdInfoSub.json");
break;
case MAV_TYPE_GROUND_ROVER:
return QStringLiteral(":/json/PX4/MavCmdInfoRover.json");
break;
default:
qWarning() << "PX4FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
return QString();
}
}
QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
......
......@@ -49,7 +49,7 @@ public:
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYS_AUTOSTART"); }
void missionCommandOverrides (QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
QString missionCommandOverrides (MAV_TYPE vehicleType) const final;
QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); }
QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
......
{
"comment": "Any Firmware, Any Vehicle",
"version": 1,
"mavCmdInfo": [
......@@ -35,6 +37,24 @@
"units": "secs",
"default": 0,
"decimalPlaces": 0
},
"param2": {
"label": "Acceptance:",
"units": "m",
"default": 3,
"decimalPlaces": 2
},
"param3": {
"label": "PassThru:",
"units": "m",
"default": 0,
"decimalPlaces": 2
},
"param4": {
"label": "Heading:",
"units": "radians",
"default": 0.0,
"decimalPlaces": 2
}
},
{
......@@ -48,7 +68,7 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 10.0,
"default": 50.0,
"decimalPlaces": 2
}
},
......@@ -68,8 +88,15 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 10.0,
"default": 50.0,
"decimalPlaces": 2
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
......@@ -89,8 +116,15 @@
"param3": {
"label": "Radius:",
"units": "m",
"default": 10.0,
"default": 50.0,
"decimalPlaces": 2
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
......@@ -113,19 +147,13 @@
"label": "Abort Alt:",
"units": "m",
"default": 25.0,
"decimalPlaces": 3
"decimalPlaces": 2
},
"param4": {
"label": "Heading:",
"units": "radians",
"default": 0.0,
"decimalPlaces": 2
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0.0,
"decimalPlaces": 2
}
},
{
......@@ -192,8 +220,15 @@
"param2": {
"label": "Radius:",
"units": "m",
"default": 10.0,
"default": 50.0,
"decimalPlaces": 2
},
"param4": {
"label": "Next waypoint start:",
"enumStrings": "Center,On Loiter",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{ "id": 32, "rawName": "MAV_CMD_DO_FOLLOW", "friendlyName": "Follow Me" },
......@@ -267,7 +302,7 @@
"units": "secs",
"default": 0,
"decimalPlaces": 0
}
}
},
{ "id": 83, "rawName": "MAV_CMD_NAV_ALTITUDE_WAIT", "friendlyName": "Altitude wait" },
{
......@@ -298,12 +333,6 @@
"units": "deg",
"default": 0.0,
"decimalPlaces": 2
},
"param7": {
"label": "Altitude:",
"units": "m",
"default": 0.0,
"decimalPlaces": 2
}
},
{
......@@ -312,11 +341,40 @@
"friendlyName": "Guided enable",
"description": "Enable/Disabled guided mode.",
"param1": {
"label": "Enable:",
"label": "Enable",
"enumStrings": "Disable,Enable",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 94,
"rawName": "MAV_CMD_NAV_DELAY",
"friendlyName": "Delay until",
"description": "Delay unti the specified time is reached.",
"param1": {
"label": "Hold:",
"units": "secs",
"default": 30,
"decimalPlaces": 0
},
"param2": {
"label": "Hour (utc):",
"default": 0,
"decimalPlaces": 0
},
"param3": {
"label": "Min (utc):",
"default": 0,
"decimalPlaces": 0
},
"param4": {
"label": "Sec (utc):",
"default": 0,
"decimalPlaces": 0
}
},
{
"id": 112,
"rawName": "MAV_CMD_CONDITION_DELAY",
......@@ -359,7 +417,7 @@
"param1": {
"label": "Distance:",
"units": "m",
"default": 0,
"default": 10,
"decimalPlaces": 2
}
},
......@@ -383,25 +441,47 @@
},
"param3": {
"label": "Direction:",
"default": 1,
"decimalPlaces": 0
"enumStrings": "Clockwise,Counter-Clockwise",
"enumValues": "1,-1",
"default": 1
},
"param3": {
"param4": {
"label": "Offset:",
"enumStrings": "Relative,Absolute",
"enumValues": "1,0",
"default": 5
"default": 1
}
},
{ "id": 159, "rawName": "MAV_CMD_CONDITION_LAST", "friendlyName": "MAV_CMD_CONDITION_LAST" },
{ "id": 176, "rawName": "MAV_CMD_DO_SET_MODE", "friendlyName": "Set mode" },
{
"id": 176,
"rawName": "MAV_CMD_DO_SET_MODE",
"friendlyName": "Set flight mode",
"description": "Set flight mode.",
"category": "Advanced",
"param1": {
"label": "Mode:",
"default": 0,
"decimalPlaces": 0
},
"param2": {
"label": "Custom Mode:",
"default": 0,
"decimalPlaces": 0
},
"param3": {
"label": "Sub Mode:",
"default": 0,
"decimalPlaces": 0
}
},
{
"id": 177,
"rawName": "MAV_CMD_DO_JUMP",
"friendlyName": "Jump to item",
"description": "Mission will continue at the specified item.",
"friendlyEdit": true,
"category": "Basic",
"category": "Advanced",
"param1": {
"label": "Item #:",
"default": 1,
......@@ -434,6 +514,12 @@
"label": "Throttle:",
"units": "%",
"default": -1
},
"param4": {
"label": "Offset:",
"enumStrings": "Relative,Absolute",
"enumValues": "1,0",
"default": 1
}
},
{
......@@ -449,8 +535,7 @@
"label": "Mode:",
"enumStrings": "Vehicle position,Specified position",
"enumValues": "1,0",
"default": 0,
"decimalPlaces": 0
"default": 0
}
},
{ "id": 180, "rawName": "MAV_CMD_DO_SET_PARAMETER", "friendlyName": "Set Parameter" },
......@@ -505,7 +590,7 @@
},
"param2": {
"label": "PWM:",
"default": 1000,
"default": 1500,
"decimalPlaces": 0
}
},
......@@ -550,6 +635,20 @@
{ "id": 191, "rawName": "MAV_CMD_DO_GO_AROUND", "friendlyName": "Go around" },
{ "id": 192, "rawName": "MAV_CMD_DO_REPOSITION", "friendlyName": "Reposition" },
{ "id": 193, "rawName": "MAV_CMD_DO_PAUSE_CONTINUE", "friendlyName": "Pause/Continue" },
{
"id": 194,
"rawName": "MAV_CMD_DO_SET_REVERSE",
"friendlyName": "Set moving direction" ,
"description": "Set moving direction to forward or reverse.",
"friendlyEdit": true,
"category": "Advanced",
"param1": {
"label": "Direction:",
"enumStrings": "Forward,Reverse",
"enumValues": "0,1",
"default": 0
}
},
{ "id": 200, "rawName": "MAV_CMD_DO_CONTROL_VIDEO", "friendlyName": "Control video" },
{
"id": 201,
......@@ -703,11 +802,13 @@
"param1": {
"label": "Lat/Pitch:",
"default": 0,
"units": "deg",
"decimalPlaces": 7
},
"param2": {
"label": "Lon/Roll:",
"default": 0,
"units": "deg",
"decimalPlaces": 7
},
"param3": {
......@@ -781,8 +882,7 @@
"label": "Inverted:",
"enumStrings": "Normal,Inverted",
"enumValues": "0,1",
"default": 0,
"decimalPlaces": 0
"default": 0
}
},
{
......@@ -802,12 +902,26 @@
"label": "Action:",
"enumStrings": "Release,Grab",
"enumValues": "0,1",
"default": 0,
"decimalPlaces": 0
"default": 0
}
},
{
"id": 212,
"rawName": "MAV_CMD_DO_AUTOTUNE_ENABLE",
"friendlyName": "AutoTune Enable",
"description": "AutoTune Enable.",
"specifiesCoordinate": false,
"friendlyEdit": true,
"category": "Advanced",
"param2": {
"label": "Enable:",
"enumStrings": "Enable,Disable",
"enumValues": "1,0",
"default": 1
}
},
{ "id": 220, "rawName": "MAV_CMD_DO_MOUNT_CONTROL_QUAT", "friendlyName": "MAV_CMD_DO_MOUNT_CONTROL_QUAT" },
{ "id": 221, "rawName": "MAV_CMD_DO_GUIDED_MASTER", "friendlyName": "MAV_CMD_DO_GUIDED_MASTER" },
{ "id": 220, "rawName": "MAV_CMD_DO_MOUNT_CONTROL_QUAT" },
{ "id": 221, "rawName": "MAV_CMD_DO_GUIDED_MASTER" },
{
"id": 222,
"rawName": "MAV_CMD_DO_GUIDED_LIMITS",
......@@ -859,14 +973,13 @@
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{
"id": 3000,
"rawName": "MAV_CMD_DO_VTOL_TRANSITION",
"rawName": "MAV_CMD_DO_VTOL_TRANSITION",
"friendlyName": "VTOL Transition",
"description": "Perform flight mode transition",
"category": "VTOL",
"param1": {
"label": "Mode:",
"default": 3,
"decimalPlaces": 0,
"enumStrings": "Hover Mode,Plane Mode",
"enumValues": "3,4"
}
......
{
"comment": "Any Firmware, Fixed Wing",
"version": 1,
"mavCmdInfo": [
{
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "4"
}
]
}
{
"comment": "Any Firmware, Multi Rotor",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, Rover",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, Sub",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, VTOL",
"version": 1,
"mavCmdInfo": [
]
}
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#include "MissionCommandList.h"
#include "FactMetaData.h"
#include "Vehicle.h"
......@@ -15,6 +14,7 @@
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include "JsonHelper.h"
#include "MissionCommandUIInfo.h"
#include <QStringList>
#include <QJsonDocument>
......@@ -23,35 +23,16 @@
#include <QDebug>
#include <QFile>
const QString MissionCommandList::_categoryJsonKey (QStringLiteral("category"));
const QString MissionCommandList::_decimalPlacesJsonKey (QStringLiteral("decimalPlaces"));
const QString MissionCommandList::_defaultJsonKey (QStringLiteral("default"));
const QString MissionCommandList::_descriptionJsonKey (QStringLiteral("description"));
const QString MissionCommandList::_enumStringsJsonKey (QStringLiteral("enumStrings"));
const QString MissionCommandList::_enumValuesJsonKey (QStringLiteral("enumValues"));
const QString MissionCommandList::_friendlyEditJsonKey (QStringLiteral("friendlyEdit"));
const QString MissionCommandList::_friendlyNameJsonKey (QStringLiteral("friendlyName"));
const QString MissionCommandList::_idJsonKey (QStringLiteral("id"));
const QString MissionCommandList::_labelJsonKey (QStringLiteral("label"));
const QString MissionCommandList::_mavCmdInfoJsonKey (QStringLiteral("mavCmdInfo"));
const QString MissionCommandList::_param1JsonKey (QStringLiteral("param1"));
const QString MissionCommandList::_param2JsonKey (QStringLiteral("param2"));
const QString MissionCommandList::_param3JsonKey (QStringLiteral("param3"));
const QString MissionCommandList::_param4JsonKey (QStringLiteral("param4"));
const QString MissionCommandList::_paramJsonKeyFormat (QStringLiteral("param%1"));
const QString MissionCommandList::_rawNameJsonKey (QStringLiteral("rawName"));
const QString MissionCommandList::_standaloneCoordinateJsonKey (QStringLiteral("standaloneCoordinate"));
const QString MissionCommandList::_specifiesCoordinateJsonKey (QStringLiteral("specifiesCoordinate"));
const QString MissionCommandList::_unitsJsonKey (QStringLiteral("units"));
const QString MissionCommandList::_versionJsonKey (QStringLiteral("version"));
MissionCommandList::MissionCommandList(const QString& jsonFilename, QObject* parent)
const char* MissionCommandList::_versionJsonKey = "version";
const char* MissionCommandList::_mavCmdInfoJsonKey = "mavCmdInfo";
MissionCommandList::MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent)
: QObject(parent)
{
_loadMavCmdInfoJson(jsonFilename);
_loadMavCmdInfoJson(jsonFilename, baseCommandList);
}
void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename)
void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool baseCommandList)
{
if (jsonFilename.isEmpty()) {
return;
......@@ -88,162 +69,43 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename)
return;
}
// Iterate over MissionCommandUIInfo objects
QJsonArray jsonArray = jsonValue.toArray();
foreach(QJsonValue info, jsonArray) {
if (!info.isObject()) {
qWarning() << jsonFilename << "mavCmdArray should contain objects";
return;
}
QJsonObject jsonObject = info.toObject();
// Make sure we have the required keys
QString errorString;
QStringList requiredKeys;
requiredKeys << _idJsonKey << _rawNameJsonKey;
if (!JsonHelper::validateRequiredKeys(jsonObject, requiredKeys, errorString)) {
qWarning() << jsonFilename << errorString;
return;
}
MissionCommandUIInfo* uiInfo = new MissionCommandUIInfo(this);
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey <<_friendlyEditJsonKey
<< _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _categoryJsonKey;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::String;
if (!JsonHelper::validateKeyTypes(jsonObject, keys, types, errorString)) {
QString errorString;
if (!uiInfo->loadJsonInfo(info.toObject(), baseCommandList, errorString)) {
uiInfo->deleteLater();
qWarning() << jsonFilename << errorString;
return;
}
MavCmdInfo* mavCmdInfo = new MavCmdInfo(this);
mavCmdInfo->_command = (MAV_CMD) jsonObject.value(_idJsonKey).toInt();
mavCmdInfo->_category = jsonObject.value(_categoryJsonKey).toString("Advanced");
mavCmdInfo->_rawName = jsonObject.value(_rawNameJsonKey).toString();
mavCmdInfo->_friendlyName = jsonObject.value(_friendlyNameJsonKey).toString(QString());
mavCmdInfo->_description = jsonObject.value(_descriptionJsonKey).toString(QString());
mavCmdInfo->_standaloneCoordinate = jsonObject.value(_standaloneCoordinateJsonKey).toBool(false);
mavCmdInfo->_specifiesCoordinate = jsonObject.value(_specifiesCoordinateJsonKey).toBool(false);
mavCmdInfo->_friendlyEdit = jsonObject.value(_friendlyEditJsonKey).toBool(false);
qCDebug(MissionCommandsLog) << "Command"
<< mavCmdInfo->_command
<< mavCmdInfo->_category
<< mavCmdInfo->_rawName
<< mavCmdInfo->_friendlyName
<< mavCmdInfo->_description
<< mavCmdInfo->_standaloneCoordinate
<< mavCmdInfo->_specifiesCoordinate
<< mavCmdInfo->_friendlyEdit;
if (_mavCmdInfoMap.contains((MAV_CMD)mavCmdInfo->command())) {
qWarning() << jsonFilename << "Duplicate command" << mavCmdInfo->command();
return;
}
_mavCmdInfoMap[mavCmdInfo->_command] = mavCmdInfo;
// Read params
for (int i=1; i<=7; i++) {
QString paramKey = QString(_paramJsonKeyFormat).arg(i);
if (jsonObject.contains(paramKey)) {
QJsonObject paramObject = jsonObject.value(paramKey).toObject();
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _defaultJsonKey << _decimalPlacesJsonKey << _enumStringsJsonKey << _enumValuesJsonKey << _labelJsonKey << _unitsJsonKey;
types << QJsonValue::Double << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String;
if (!JsonHelper::validateKeyTypes(jsonObject, keys, types, errorString)) {
qWarning() << jsonFilename << errorString;
return;
}
mavCmdInfo->_friendlyEdit = true; // Assume friendly edit if we have params
if (!paramObject.contains(_labelJsonKey)) {
qWarning() << jsonFilename << "param object missing label key" << mavCmdInfo->rawName() << paramKey;
return;
}
MavCmdParamInfo* paramInfo = new MavCmdParamInfo(this);
paramInfo->_label = paramObject.value(_labelJsonKey).toString();
paramInfo->_defaultValue = paramObject.value(_defaultJsonKey).toDouble(0.0);
paramInfo->_decimalPlaces = paramObject.value(_decimalPlacesJsonKey).toInt(FactMetaData::unknownDecimalPlaces);
paramInfo->_enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
paramInfo->_param = i;
paramInfo->_units = paramObject.value(_unitsJsonKey).toString();
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
foreach (const QString &enumValue, enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);
if (!convertOk) {
qWarning() << jsonFilename << "Bad enumValue" << enumValue;
return;
}
paramInfo->_enumValues << QVariant(value);
}
if (paramInfo->_enumValues.count() != paramInfo->_enumStrings.count()) {
qWarning() << jsonFilename << "enum strings/values count mismatch" << paramInfo->_enumStrings.count() << paramInfo->_enumValues.count();
return;
}
qCDebug(MissionCommandsLog) << "Param"
<< paramInfo->_label
<< paramInfo->_defaultValue
<< paramInfo->_decimalPlaces
<< paramInfo->_param
<< paramInfo->_units
<< paramInfo->_enumStrings
<< paramInfo->_enumValues;
mavCmdInfo->_paramInfoMap[i] = paramInfo;
}
// Update list of known categories
QString newCategory = uiInfo->category();
if (!newCategory.isEmpty() && !_categories.contains(newCategory)) {
_categories.append(newCategory);
}
if (mavCmdInfo->friendlyEdit()) {
if (mavCmdInfo->description().isEmpty()) {
qWarning() << jsonFilename << "Missing description" << mavCmdInfo->rawName();
return;
}
if (mavCmdInfo->rawName() == mavCmdInfo->friendlyName()) {
qWarning() << jsonFilename << "Missing friendly name" << mavCmdInfo->rawName() << mavCmdInfo->friendlyName();
return;
}
}
_infoMap[uiInfo->command()] = uiInfo;
}
}
bool MissionCommandList::contains(MAV_CMD command) const
{
return _mavCmdInfoMap.contains(command);
}
MavCmdInfo* MissionCommandList::getMavCmdInfo(MAV_CMD command) const
{
if (!contains(command)) {
return NULL;
// Build id list
foreach (MAV_CMD id, _infoMap.keys()) {
_ids << id;
}
return _mavCmdInfoMap[command];
}
QList<MAV_CMD> MissionCommandList::commandsIds(void) const
MissionCommandUIInfo* MissionCommandList::getUIInfo(MAV_CMD command) const
{
QList<MAV_CMD> list;
foreach (const MavCmdInfo* mavCmdInfo, _mavCmdInfoMap) {
list << (MAV_CMD)mavCmdInfo->command();
if (!_infoMap.contains(command)) {
return NULL;
}
return list;
return _infoMap[command];
}
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#ifndef MissionCommandList_H
#define MissionCommandList_H
......@@ -22,139 +21,35 @@
#include <QJsonObject>
#include <QJsonValue>
class MissionCommandList;
class Vehicle;
/// The information associated with a mission command parameter.
class MavCmdParamInfo : public QObject {
Q_OBJECT
public:
MavCmdParamInfo(QObject* parent = NULL)
: QObject(parent)
{
}
class MissionCommandUIInfo;
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
Q_PROPERTY(double defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(QStringList enumStrings READ enumStrings CONSTANT)
Q_PROPERTY(QVariantList enumValues READ enumValues CONSTANT)
Q_PROPERTY(QString label READ label CONSTANT)
Q_PROPERTY(int param READ param CONSTANT)
Q_PROPERTY(QString units READ units CONSTANT)
int decimalPlaces (void) const { return _decimalPlaces; }
double defaultValue (void) const { return _defaultValue; }
QStringList enumStrings (void) const { return _enumStrings; }
QVariantList enumValues (void) const { return _enumValues; }
QString label (void) const { return _label; }
int param (void) const { return _param; }
QString units (void) const { return _units; }
private:
int _decimalPlaces;
double _defaultValue;
QStringList _enumStrings;
QVariantList _enumValues;
QString _label;
int _param;
QString _units;
friend class MissionCommandList;
};
// The information associated with a mission command.
class MavCmdInfo : public QObject {
Q_OBJECT
public:
MavCmdInfo(QObject* parent = NULL)
: QObject(parent)
{
}
Q_PROPERTY(QString category READ category CONSTANT)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ qmlCommand CONSTANT)
Q_PROPERTY(QString description READ description CONSTANT)
Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT)
Q_PROPERTY(QString friendlyName READ friendlyName CONSTANT)
Q_PROPERTY(QString rawName READ rawName CONSTANT)
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
MavlinkQmlSingleton::Qml_MAV_CMD qmlCommand(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; }
MAV_CMD command(void) const { return _command; }
QString category (void) const { return _category; }
QString description (void) const { return _description; }
bool friendlyEdit (void) const { return _friendlyEdit; }
QString friendlyName (void) const { return _friendlyName; }
QString rawName (void) const { return _rawName; }
bool isStandaloneCoordinate(void) const { return _standaloneCoordinate; }
bool specifiesCoordinate (void) const { return _specifiesCoordinate; }
const QMap<int, MavCmdParamInfo*>& paramInfoMap(void) const { return _paramInfoMap; }
private:
QString _category;
MAV_CMD _command;
QString _description;
bool _friendlyEdit;
QString _friendlyName;
QMap<int, MavCmdParamInfo*> _paramInfoMap;
QString _rawName;
bool _standaloneCoordinate;
bool _specifiesCoordinate;
friend class MissionCommandList;
};
// A list of mission command info loaded from a json file.
/// Maintains a list of MissionCommandUIInfo objects loaded from a json file.
class MissionCommandList : public QObject
{
Q_OBJECT
public:
MissionCommandList(const QString& jsonFilename, QObject* parent = NULL);
/// @param jsonFilename Json file which contains commands
/// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy
MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = NULL);
Q_INVOKABLE bool contains(MavlinkQmlSingleton::Qml_MAV_CMD command) const { return contains((MAV_CMD)command); }
bool contains(MAV_CMD command) const;
/// Returns list of categories in this list
QStringList& categories(void) { return _categories; }
Q_INVOKABLE QVariant getMavCmdInfo(MavlinkQmlSingleton::Qml_MAV_CMD command) const { return QVariant::fromValue(getMavCmdInfo((MAV_CMD)command)); }
MavCmdInfo* getMavCmdInfo(MAV_CMD command) const;
/// Returns the ui info for specified command, NULL if command not found
MissionCommandUIInfo* getUIInfo(MAV_CMD command) const;
QList<MAV_CMD> commandsIds(void) const;
const QList<MAV_CMD>& commandIds(void) const { return _ids; }
private:
void _loadMavCmdInfoJson(const QString& jsonFilename);
void _loadMavCmdInfoJson(const QString& jsonFilename, bool baseCommandList);
private:
QMap<MAV_CMD, MavCmdInfo*> _mavCmdInfoMap;
QMap<MAV_CMD, MissionCommandUIInfo*> _infoMap;
QList<MAV_CMD> _ids;
QStringList _categories;
static const QString _categoryJsonKey;
static const QString _decimalPlacesJsonKey;
static const QString _defaultJsonKey;
static const QString _descriptionJsonKey;
static const QString _enumStringsJsonKey;
static const QString _enumValuesJsonKey;
static const QString _friendlyNameJsonKey;
static const QString _friendlyEditJsonKey;
static const QString _idJsonKey;
static const QString _labelJsonKey;
static const QString _mavCmdInfoJsonKey;
static const QString _param1JsonKey;
static const QString _param2JsonKey;
static const QString _param3JsonKey;
static const QString _param4JsonKey;
static const QString _paramJsonKeyFormat;
static const QString _rawNameJsonKey;
static const QString _standaloneCoordinateJsonKey;
static const QString _specifiesCoordinateJsonKey;
static const QString _unitsJsonKey;
static const QString _versionJsonKey;
static const char* _versionJsonKey;
static const char* _mavCmdInfoJsonKey;
};
#endif
/****************************************************************************
*
* (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 "MissionCommandTree.h"
#include "FactMetaData.h"
#include "Vehicle.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include "MissionCommandUIInfo.h"
#include "MissionCommandList.h"
#include <QQmlEngine>
MissionCommandTree::MissionCommandTree(QGCApplication* app, bool unitTest)
: QGCTool(app)
, _unitTest(unitTest)
{
}
void MissionCommandTree::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
#ifdef UNITTEST_BUILD
if (_unitTest) {
// Load unit testing tree
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC] = new MissionCommandList(":/json/unittest/MavCmdInfoCommon.json", true, this);
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_FIXED_WING] = new MissionCommandList(":/json/unittest/MavCmdInfoFixedWing.json", false, this);
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_QUADROTOR] = new MissionCommandList(":/json/unittest/MavCmdInfoMultiRotor.json", false, this);
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_VTOL_QUADROTOR] = new MissionCommandList(":/json/unittest/MavCmdInfoVTOL.json", false, this);
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_SUBMARINE] = new MissionCommandList(":/json/unittest/MavCmdInfoSub.json", false, this);
_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GROUND_ROVER] = new MissionCommandList(":/json/unittest/MavCmdInfoRover.json", false, this);
} else {
#endif
// Load all levels of hierarchy
foreach (MAV_AUTOPILOT firmwareType, _toolbox->firmwarePluginManager()->knownFirmwareTypes()) {
FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
QList<MAV_TYPE> vehicleTypes;
vehicleTypes << MAV_TYPE_GENERIC << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE;
foreach(MAV_TYPE vehicleType, vehicleTypes) {
QString overrideFile = plugin->missionCommandOverrides(vehicleType);
if (!overrideFile.isEmpty()) {
_staticCommandTree[firmwareType][vehicleType] = new MissionCommandList(overrideFile, firmwareType == MAV_AUTOPILOT_GENERIC && vehicleType == MAV_TYPE_GENERIC /* baseCommandList */, this);
}
}
}
#ifdef UNITTEST_BUILD
}
#endif
}
MAV_AUTOPILOT MissionCommandTree::_baseFirmwareType(MAV_AUTOPILOT firmwareType) const
{
if (qgcApp()->toolbox()->firmwarePluginManager()->knownFirmwareTypes().contains(firmwareType)) {
return firmwareType;
} else {
return MAV_AUTOPILOT_GENERIC;
}
}
MAV_TYPE MissionCommandTree::_baseVehicleType(MAV_TYPE mavType) const
{
if (QGCMAVLink::isFixedWing(mavType)) {
return MAV_TYPE_FIXED_WING;
} else if (QGCMAVLink::isMultiRotor(mavType)) {
return MAV_TYPE_QUADROTOR;
} else if (QGCMAVLink::isVTOL(mavType)) {
return MAV_TYPE_VTOL_QUADROTOR;
} else if (QGCMAVLink::isRover(mavType)) {
return MAV_TYPE_GROUND_ROVER;
} else if (QGCMAVLink::isSub(mavType)) {
return MAV_TYPE_SUBMARINE;
} else {
return MAV_TYPE_GENERIC;
}
}
/// Add the next level of the hierarchy to a collapsed tree.
/// @param vehicle Collapsed tree is for this vehicle
/// @param cmdList List of mission commands to collapse into ui info
/// @param collapsedTree Tree we are collapsing into
void MissionCommandTree::_collapseHierarchy(Vehicle* vehicle,
const MissionCommandList* cmdList,
QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
foreach (MAV_CMD command, cmdList->commandIds()) {
MissionCommandUIInfo* uiInfo = cmdList->getUIInfo(command);
if (uiInfo) {
if (collapsedTree.contains(command)) {
collapsedTree[command]->_overrideInfo(uiInfo);
} else {
collapsedTree[command] = new MissionCommandUIInfo(*uiInfo);
}
}
}
}
void MissionCommandTree::_buildAvailableCommands(Vehicle* vehicle)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
if (_availableCommands.contains(baseFirmwareType) &&
_availableCommands[baseFirmwareType].contains(baseVehicleType)) {
// Available commands list already built
return;
}
// Build new available commands list
QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree = _availableCommands[baseFirmwareType][baseVehicleType];
// Any Firmware, Any Vehicle
_collapseHierarchy(vehicle, _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC], collapsedTree);
// Any Firmware, Specific Vehicle
if (baseVehicleType != MAV_TYPE_GENERIC) {
_collapseHierarchy(vehicle, _staticCommandTree[MAV_AUTOPILOT_GENERIC][baseVehicleType], collapsedTree);
}
// Known Firmware, Any Vehicle
if (baseFirmwareType != MAV_AUTOPILOT_GENERIC) {
_collapseHierarchy(vehicle, _staticCommandTree[baseFirmwareType][MAV_TYPE_GENERIC], collapsedTree);
// Known Firmware, Specific Vehicle
if (baseVehicleType != MAV_TYPE_GENERIC) {
_collapseHierarchy(vehicle, _staticCommandTree[baseFirmwareType][baseVehicleType], collapsedTree);
}
}
// Build category list
QMapIterator<MAV_CMD, MissionCommandUIInfo*> iter(collapsedTree);
while (iter.hasNext()) {
iter.next();
QString newCategory = iter.value()->category();
if (!_availableCategories[baseFirmwareType][baseVehicleType].contains(newCategory)) {
_availableCategories[baseFirmwareType][baseVehicleType].append(newCategory);
}
}
}
QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
return _availableCategories[baseFirmwareType][baseVehicleType];
}
QString MissionCommandTree::friendlyName(MAV_CMD command)
{
MissionCommandList * commandList = _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC];
MissionCommandUIInfo* uiInfo = commandList->getUIInfo(command);
return uiInfo->friendlyName();
}
QString MissionCommandTree::rawName(MAV_CMD command)
{
MissionCommandList * commandList = _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC];
MissionCommandUIInfo* uiInfo = commandList->getUIInfo(command);
return uiInfo->rawName();
}
const QList<MAV_CMD>& MissionCommandTree::allCommandIds(void) const
{
return _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC]->commandIds();
}
const MissionCommandUIInfo* MissionCommandTree::getUIInfo(Vehicle* vehicle, MAV_CMD command)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _availableCommands[baseFirmwareType][baseVehicleType];
if (infoMap.contains(command)) {
return infoMap[command];
} else {
return NULL;
}
}
QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const QString& category)
{
MAV_AUTOPILOT baseFirmwareType;
MAV_TYPE baseVehicleType;
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
_buildAvailableCommands(vehicle);
QVariantList list;
QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _availableCommands[baseFirmwareType][baseVehicleType];
foreach (MAV_CMD command, commandMap.keys()) {
MissionCommandUIInfo* uiInfo = commandMap[command];
if (uiInfo->category() == category) {
list.append(QVariant::fromValue(uiInfo));
}
}
return list;
}
void MissionCommandTree::_baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const
{
if (vehicle) {
baseFirmwareType = _baseFirmwareType(vehicle->firmwareType());
baseVehicleType = _baseVehicleType(vehicle->vehicleType());
} else {
// No Vehicle means offline editing
baseFirmwareType = _baseFirmwareType((MAV_AUTOPILOT)QGroundControlQmlGlobal::offlineEditingFirmwareType()->rawValue().toInt());
baseVehicleType = _baseVehicleType((MAV_TYPE)QGroundControlQmlGlobal::offlineEditingVehicleType()->rawValue().toInt());
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef MissionCommandTree_H
#define MissionCommandTree_H
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include "Vehicle.h"
#include <QVariantList>
#include <QMap>
class MissionCommandUIInfo;
class MissionCommandList;
#ifdef UNITTEST_BUILD
class MissionCommandTreeTest;
#endif
/// Manages a hierarchy of MissionCommandUIInfo.
///
/// The static hierarchy allows for overriding mission command ui info based on MAV_AUTOPILOT and MAV_TYPE. The hierarchy of the tree is:
/// Any Firmware, Any Vehicle - Base set of all command definitions for any firmware, any vehicle, essentially ui defined to mavlink spec
/// Any Firmware, Fixed Wing
/// Known Firmware, Fixed Wing
/// Any Firmware, Multi Rotor (all types)
/// Known Firmware, Multi Rotor (all types)
/// Any Firmware, VTOL (all types)
/// Known Firmware, VTOL (all types)
/// Any Firmware, Rover
/// Known Firmware, Rover
/// Any Firmware, Sub
/// Known Firmware, Sub
/// For known firmwares, the override files are requested from the FirmwarePlugin.
///
/// When ui info is requested for a specific vehicle the static hierarchy in _staticCommandTree is collapsed into the set of available commands in
/// _availableCommands taking into account the appropriate set of overrides for the MAV_AUTOPILOT/MAV_TYPE combination associated with the vehicle.
///
class MissionCommandTree : public QGCTool
{
Q_OBJECT
public:
MissionCommandTree(QGCApplication* app, bool unitTest = false);
/// Returns the friendly name for the specified command
QString friendlyName(MAV_CMD command);
/// Returns the raw name for the specified command
QString rawName(MAV_CMD command);
const QList<MAV_CMD>& allCommandIds(void) const;
Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); }
const MissionCommandUIInfo* getUIInfo(Vehicle* vehicle, MAV_CMD command);
Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category);
// Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox);
private:
void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree);
MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const;
MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const;
void _buildAvailableCommands(Vehicle* vehicle);
QStringList _availableCategoriesForVehicle(Vehicle* vehicle);
void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const;
private:
/// List of all known command ids (not vehicle specific)
QList<int> _allCommandIds;
/// Full hierarchy
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, MissionCommandList*>> _staticCommandTree;
/// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _availableCommands;
/// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList>> _availableCategories;
bool _unitTest; ///< true: running in unit test mode
#ifdef UNITTEST_BUILD
friend class MissionCommandTreeTest;
#endif
};
#endif
/****************************************************************************
*
* (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 "MissionCommandTreeTest.h"
#include "QGCApplication.h"
#include "MissionCommandUIInfo.h"
#include "MissionCommandList.h"
#include "FactMetaData.h"
MissionCommandTreeTest::MissionCommandTreeTest(void)
{
}
void MissionCommandTreeTest::init(void)
{
_commandTree = new MissionCommandTree(qgcApp(), true /* unitTest */);
_commandTree->setToolbox(qgcApp()->toolbox());
}
void MissionCommandTreeTest::cleanup(void)
{
delete _commandTree;
}
QString MissionCommandTreeTest::_rawName(int id)
{
return QString("UNITTEST_%1").arg(id);
}
QString MissionCommandTreeTest::_friendlyName(int id)
{
return QString("Unit Test %1").arg(id);
}
QString MissionCommandTreeTest::_paramLabel(int index)
{
return QString("param%1").arg(index);
}
/// Verifies that all values have been set
void MissionCommandTreeTest::_checkFullInfoMap(const MissionCommandUIInfo* uiInfo)
{
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_rawNameJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_categoryJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_descriptionJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_friendlyEditJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_friendlyNameJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_standaloneCoordinateJsonKey));
QVERIFY(uiInfo->_infoMap.contains(MissionCommandUIInfo::_specifiesCoordinateJsonKey));
}
// Verifies that values match settings for base tree
void MissionCommandTreeTest::_checkBaseValues(const MissionCommandUIInfo* uiInfo, int command)
{
QVERIFY(uiInfo != NULL);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)command);
QCOMPARE(uiInfo->rawName(), _rawName(command));
QCOMPARE(uiInfo->category(), QStringLiteral("category"));
QCOMPARE(uiInfo->description(), QStringLiteral("description"));
QCOMPARE(uiInfo->friendlyEdit(), true);
QCOMPARE(uiInfo->friendlyName(), _friendlyName(command));
QCOMPARE(uiInfo->isStandaloneCoordinate(), true);
QCOMPARE(uiInfo->specifiesCoordinate(), true);
for (int i=1; i<=7; i++) {
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i);
QVERIFY(paramInfo);
QCOMPARE(paramInfo->decimalPlaces(), 1);
QCOMPARE(paramInfo->defaultValue(), 1.0);
QCOMPARE(paramInfo->enumStrings().count(), 2);
QCOMPARE(paramInfo->enumStrings()[0], QStringLiteral("1"));
QCOMPARE(paramInfo->enumStrings()[1], QStringLiteral("2"));
QCOMPARE(paramInfo->enumValues().count(), 2);
QCOMPARE(paramInfo->enumValues()[0].toDouble(), 1.0);
QCOMPARE(paramInfo->enumValues()[1].toDouble(), 2.0);
QCOMPARE(paramInfo->label(), _paramLabel(i));
QCOMPARE(paramInfo->param(), i);
QCOMPARE(paramInfo->units(), QStringLiteral("units"));
}
}
// Verifies that values match settings for an override
void MissionCommandTreeTest::_checkOverrideParamValues(const MissionCommandUIInfo* uiInfo, int command, int paramIndex)
{
QString overrideString = QString("override fw %1 %2").arg(command).arg(paramIndex);
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(paramIndex);
QVERIFY(paramInfo);
QCOMPARE(paramInfo->decimalPlaces(), 1);
QCOMPARE(paramInfo->defaultValue(), 1.0);
QCOMPARE(paramInfo->enumStrings().count(), 2);
QCOMPARE(paramInfo->enumStrings()[0], QStringLiteral("1"));
QCOMPARE(paramInfo->enumStrings()[1], QStringLiteral("2"));
QCOMPARE(paramInfo->enumValues().count(), 2);
QCOMPARE(paramInfo->enumValues()[0].toDouble(), 1.0);
QCOMPARE(paramInfo->enumValues()[1].toDouble(), 2.0);
QCOMPARE(paramInfo->label(), overrideString);
QCOMPARE(paramInfo->param(), paramIndex);
QCOMPARE(paramInfo->units(), overrideString);
}
// Verifies that values match settings for an override
void MissionCommandTreeTest::_checkOverrideValues(const MissionCommandUIInfo* uiInfo, int command)
{
QString overrideString = QString("override fw %1").arg(command);
QVERIFY(uiInfo != NULL);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)command);
QCOMPARE(uiInfo->rawName(), _rawName(command));
QCOMPARE(uiInfo->category(), overrideString);
QCOMPARE(uiInfo->description(), overrideString);
QCOMPARE(uiInfo->friendlyEdit(), true);
QCOMPARE(uiInfo->friendlyName(), _friendlyName(command));
QCOMPARE(uiInfo->isStandaloneCoordinate(), false);
QCOMPARE(uiInfo->specifiesCoordinate(), false);
QVERIFY(uiInfo->getParamInfo(2) == NULL);
QVERIFY(uiInfo->getParamInfo(4) == NULL);
QVERIFY(uiInfo->getParamInfo(6) == NULL);
_checkOverrideParamValues(uiInfo, command, 1);
_checkOverrideParamValues(uiInfo, command, 3);
_checkOverrideParamValues(uiInfo, command, 5);
}
void MissionCommandTreeTest::testJsonLoad(void)
{
// Test loading from the bad command list
MissionCommandList* commandList = _commandTree->_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC];
QVERIFY(commandList != NULL);
// Command 1 should have all values defaulted, no params
MissionCommandUIInfo* uiInfo = commandList->getUIInfo((MAV_CMD)1);
QVERIFY(uiInfo != NULL);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)1);
QCOMPARE(uiInfo->rawName(), _rawName(1));
QVERIFY(uiInfo->category() == MissionCommandUIInfo::_advancedCategory);
QVERIFY(uiInfo->description().isEmpty());
QCOMPARE(uiInfo->friendlyEdit(), false);
QCOMPARE(uiInfo->friendlyName(), uiInfo->rawName());
QCOMPARE(uiInfo->isStandaloneCoordinate(), false);
QCOMPARE(uiInfo->specifiesCoordinate(), false);
for (int i=1; i<=7; i++) {
QVERIFY(uiInfo->getParamInfo(i) == NULL);
}
// Command 2 should all values defaulted for param 1
uiInfo = commandList->getUIInfo((MAV_CMD)2);
QVERIFY(uiInfo != NULL);
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(1);
QVERIFY(paramInfo);
QCOMPARE(paramInfo->decimalPlaces(), -1);
QCOMPARE(paramInfo->defaultValue(), 0.0);
QCOMPARE(paramInfo->enumStrings().count(), 0);
QCOMPARE(paramInfo->enumValues().count(), 0);
QCOMPARE(paramInfo->label(), _paramLabel(1));
QCOMPARE(paramInfo->param(), 1);
QVERIFY(paramInfo->units().isEmpty());
for (int i=2; i<=7; i++) {
QVERIFY(uiInfo->getParamInfo(i) == NULL);
}
// Command 3 should have all values set
_checkBaseValues(commandList->getUIInfo((MAV_CMD)3), 3);
}
void MissionCommandTreeTest::testOverride(void)
{
// Generic/Generic should not have any overrides
Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC);
_checkBaseValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4);
delete vehicle;
// Generic/FixedWing should have overrides
vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_FIXED_WING);
_checkOverrideValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4);
delete vehicle;
}
void MissionCommandTreeTest::testAllTrees(void)
{
QList<MAV_AUTOPILOT> firmwareList;
QList<MAV_TYPE> vehicleList;
firmwareList << MAV_AUTOPILOT_GENERIC << MAV_AUTOPILOT_PX4 << MAV_AUTOPILOT_ARDUPILOTMEGA;
vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_QUADROTOR;
// This will cause all of the variants of collapsed trees to be built
foreach(MAV_AUTOPILOT firmwareType, firmwareList) {
foreach (MAV_TYPE vehicleType, vehicleList) {
Vehicle* vehicle = new Vehicle(firmwareType, vehicleType);
qDebug() << firmwareType << vehicleType;
QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL);
delete vehicle;
}
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef MissionCommandTreeTest_H
#define MissionCommandTreeTest_H
#include "UnitTest.h"
#include "MissionCommandTree.h"
/// Unit test for the MissionItem Object
class MissionCommandTreeTest : public UnitTest
{
Q_OBJECT
public:
MissionCommandTreeTest(void);
private slots:
void init(void);
void cleanup(void);
void testJsonLoad(void);
void testOverride(void);
void testAllTrees(void);
private:
QString _rawName(int id);
QString _friendlyName(int id);
QString _paramLabel(int index);
void _checkFullInfoMap(const MissionCommandUIInfo* uiInfo);
void _checkBaseValues(const MissionCommandUIInfo* uiInfo, int command);
void _checkOverrideValues(const MissionCommandUIInfo* uiInfo, int command);
void _checkOverrideParamValues(const MissionCommandUIInfo* uiInfo, int command, int paramIndex);
MissionCommandTree* _commandTree;
};
#endif
/****************************************************************************
*
* (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 "MissionCommandUIInfo.h"
#include "JsonHelper.h"
#include "FactMetaData.h"
#include "QGCLoggingCategory.h"
const char* MissionCommandUIInfo::_categoryJsonKey = "category";
const char* MissionCommandUIInfo::_decimalPlacesJsonKey = "decimalPlaces";
const char* MissionCommandUIInfo::_defaultJsonKey = "default";
const char* MissionCommandUIInfo::_descriptionJsonKey = "description";
const char* MissionCommandUIInfo::_enumStringsJsonKey = "enumStrings";
const char* MissionCommandUIInfo::_enumValuesJsonKey = "enumValues";
const char* MissionCommandUIInfo::_friendlyEditJsonKey = "friendlyEdit";
const char* MissionCommandUIInfo::_friendlyNameJsonKey = "friendlyName";
const char* MissionCommandUIInfo::_idJsonKey = "id";
const char* MissionCommandUIInfo::_labelJsonKey = "label";
const char* MissionCommandUIInfo::_mavCmdInfoJsonKey = "mavCmdInfo";
const char* MissionCommandUIInfo::_param1JsonKey = "param1";
const char* MissionCommandUIInfo::_param2JsonKey = "param2";
const char* MissionCommandUIInfo::_param3JsonKey = "param3";
const char* MissionCommandUIInfo::_param4JsonKey = "param4";
const char* MissionCommandUIInfo::_param5JsonKey = "param5";
const char* MissionCommandUIInfo::_param6JsonKey = "param6";
const char* MissionCommandUIInfo::_param7JsonKey = "param7";
const char* MissionCommandUIInfo::_paramJsonKeyFormat = "param%1";
const char* MissionCommandUIInfo::_paramRemoveJsonKey = "paramRemove";
const char* MissionCommandUIInfo::_rawNameJsonKey = "rawName";
const char* MissionCommandUIInfo::_standaloneCoordinateJsonKey = "standaloneCoordinate";
const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoordinate";
const char* MissionCommandUIInfo::_unitsJsonKey = "units";
const char* MissionCommandUIInfo::_commentJsonKey = "comment";
const char* MissionCommandUIInfo::_advancedCategory = "Advanced";
MissionCmdParamInfo::MissionCmdParamInfo(QObject* parent)
: QObject(parent)
{
}
MissionCmdParamInfo::MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent)
: QObject(parent)
{
*this = other;
}
const MissionCmdParamInfo& MissionCmdParamInfo::operator=(const MissionCmdParamInfo& other)
{
_decimalPlaces = other._decimalPlaces;
_defaultValue = other._defaultValue;
_enumStrings = other._enumStrings;
_enumValues = other._enumValues;
_label = other._label;
_param = other._param;
_units = other._units;
return *this;
}
MissionCommandUIInfo::MissionCommandUIInfo(QObject* parent)
: QObject(parent)
{
}
MissionCommandUIInfo::MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent)
: QObject(parent)
{
*this = other;
}
const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommandUIInfo& other)
{
_command = other._command;
_infoMap = other._infoMap;
_paramRemoveList = other._paramRemoveList;
foreach (int index, other._paramInfoMap.keys()) {
_paramInfoMap[index] = new MissionCmdParamInfo(*other._paramInfoMap[index], this);
}
return *this;
}
QString MissionCommandUIInfo::category(void) const
{
if (_infoMap.contains(_categoryJsonKey)) {
return _infoMap[_categoryJsonKey].toString();
} else {
return _advancedCategory;
}
}
QString MissionCommandUIInfo::description(void) const
{
if (_infoMap.contains(_descriptionJsonKey)) {
return _infoMap[_descriptionJsonKey].toString();
} else {
return QString();
}
}
bool MissionCommandUIInfo::friendlyEdit(void) const
{
if (_infoMap.contains(_friendlyEditJsonKey)) {
return _infoMap[_friendlyEditJsonKey].toBool();
} else {
return false;
}
}
QString MissionCommandUIInfo::friendlyName(void) const
{
if (_infoMap.contains(_friendlyNameJsonKey)) {
return _infoMap[_friendlyNameJsonKey].toString();
} else {
return QString();
}
}
QString MissionCommandUIInfo::rawName(void) const
{
if (_infoMap.contains(_rawNameJsonKey)) {
return _infoMap[_rawNameJsonKey].toString();
} else {
return QString();
}
}
bool MissionCommandUIInfo::isStandaloneCoordinate(void) const
{
if (_infoMap.contains(_standaloneCoordinateJsonKey)) {
return _infoMap[_standaloneCoordinateJsonKey].toBool();
} else {
return false;
}
}
bool MissionCommandUIInfo::specifiesCoordinate (void) const
{
if (_infoMap.contains(_specifiesCoordinateJsonKey)) {
return _infoMap[_specifiesCoordinateJsonKey].toBool();
} else {
return false;
}
}
void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo)
{
// Override info values
foreach (const QString& valueKey, uiInfo->_infoMap.keys()) {
_setInfoValue(valueKey, uiInfo->_infoMap[valueKey]);
}
// Add to the remove params list
foreach (int removeIndex, uiInfo->_paramRemoveList) {
if (!_paramRemoveList.contains(removeIndex)) {
_paramRemoveList.append(removeIndex);
}
}
// Override param info
foreach (const int paramIndex, uiInfo->_paramInfoMap.keys()) {
_paramRemoveList.removeOne(paramIndex);
// MissionCmdParamInfo objects are owned by MissionCommandTree are are in existence for the entire run so
// we can just use the same pointer reference.
_paramInfoMap[paramIndex] = uiInfo->_paramInfoMap[paramIndex];
}
}
QString MissionCommandUIInfo::_loadErrorString(const QString& errorString) const
{
return QString("%1 %2").arg(_infoValue(_rawNameJsonKey).toString()).arg(errorString);
}
bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requireFullObject, QString& errorString)
{
QString internalError;
QStringList allKeys;
allKeys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey
<<_friendlyEditJsonKey << _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _param5JsonKey << _param6JsonKey << _param7JsonKey
<< _paramRemoveJsonKey << _categoryJsonKey;
// Look for unknown keys in top level object
foreach (const QString& key, jsonObject.keys()) {
if (!allKeys.contains(key) && key != _commentJsonKey) {
errorString = _loadErrorString(QString("Unknown key: %1").arg(key));
return false;
}
}
// Make sure we have the required keys
QStringList requiredKeys;
requiredKeys << _idJsonKey;
if (requireFullObject) {
requiredKeys << _rawNameJsonKey;
}
if (!JsonHelper::validateRequiredKeys(jsonObject, requiredKeys, internalError)) {
errorString = _loadErrorString(internalError);
return false;
}
// Only the full object should specify rawName, friendlyName
if (!requireFullObject && (jsonObject.contains(_rawNameJsonKey) || jsonObject.contains(_friendlyNameJsonKey))) {
errorString = _loadErrorString(QStringLiteral("Only the full object should specify rawName or friendlyName"));
return false;
}
// Validate key types
QList<QJsonValue::Type> types;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object
<< QJsonValue::String << QJsonValue::String;
if (!JsonHelper::validateKeyTypes(jsonObject, allKeys, types, internalError)) {
errorString = _loadErrorString(internalError);
return false;
}
// Read in top level values
_command = (MAV_CMD)jsonObject.value(_idJsonKey).toInt();
if (jsonObject.contains(_categoryJsonKey)) {
_infoMap[_categoryJsonKey] = jsonObject.value(_categoryJsonKey).toVariant();
}
if (jsonObject.contains(_rawNameJsonKey)) {
_infoMap[_rawNameJsonKey] = jsonObject.value(_rawNameJsonKey).toVariant();
}
if (jsonObject.contains(_friendlyNameJsonKey)) {
_infoMap[_friendlyNameJsonKey] = jsonObject.value(_friendlyNameJsonKey).toVariant();
}
if (jsonObject.contains(_descriptionJsonKey)) {
_infoMap[_descriptionJsonKey] = jsonObject.value(_descriptionJsonKey).toVariant();
}
if (jsonObject.contains(_standaloneCoordinateJsonKey)) {
_infoMap[_standaloneCoordinateJsonKey] = jsonObject.value(_standaloneCoordinateJsonKey).toVariant();
}
if (jsonObject.contains(_specifiesCoordinateJsonKey)) {
_infoMap[_specifiesCoordinateJsonKey] = jsonObject.value(_specifiesCoordinateJsonKey).toVariant();
}
if (jsonObject.contains(_friendlyEditJsonKey)) {
_infoMap[_friendlyEditJsonKey] = jsonObject.value(_friendlyEditJsonKey).toVariant();
}
if (jsonObject.contains(_paramRemoveJsonKey)) {
QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(","));
foreach (const QString& indexString, indexList) {
_paramRemoveList.append(indexString.toInt());
}
}
if (requireFullObject) {
// Since this is the base of the hierarchy it must contain valid defaults for all values.
if (!_infoAvailable(_categoryJsonKey)) {
_setInfoValue(_categoryJsonKey, _advancedCategory);
}
if (!_infoAvailable(_friendlyNameJsonKey)) {
_setInfoValue(_friendlyNameJsonKey, _infoValue(_rawNameJsonKey));
}
if (!_infoAvailable(_descriptionJsonKey)) {
_setInfoValue(_descriptionJsonKey, QStringLiteral(""));
}
if (!_infoAvailable(_standaloneCoordinateJsonKey)) {
_setInfoValue(_standaloneCoordinateJsonKey, false);
}
if (!_infoAvailable(_specifiesCoordinateJsonKey)) {
_setInfoValue(_specifiesCoordinateJsonKey, false);
}
if (!_infoAvailable(_friendlyEditJsonKey)) {
_setInfoValue(_friendlyEditJsonKey, false);
}
}
if (requireFullObject) {
if (_infoAvailable(_friendlyEditJsonKey) && _infoValue(_friendlyEditJsonKey).toBool()) {
if (!_infoAvailable(_descriptionJsonKey)) {
errorString = _loadErrorString(QStringLiteral("Missing description for friendly edit"));
return false;
}
if (_infoValue(_rawNameJsonKey).toString() == _infoValue(_friendlyNameJsonKey).toString()) {
errorString = _loadErrorString(QStringLiteral("Missing friendlyName for friendly edit"));
return false;
}
}
}
QString debugOutput;
foreach (const QString& infoKey, _infoMap.keys()) {
debugOutput.append(QString("MavCmdInfo %1: %2 ").arg(infoKey).arg(_infoMap[infoKey].toString()));
}
qCDebug(MissionCommandsLog) << debugOutput;
// Read params
for (int i=1; i<=7; i++) {
QString paramKey = QString(_paramJsonKeyFormat).arg(i);
if (jsonObject.contains(paramKey)) {
QJsonObject paramObject = jsonObject.value(paramKey).toObject();
QStringList allParamKeys;
allParamKeys << _defaultJsonKey << _decimalPlacesJsonKey << _enumStringsJsonKey << _enumValuesJsonKey << _labelJsonKey << _unitsJsonKey;
// Look for unknown keys in param object
foreach (const QString& key, paramObject.keys()) {
if (!allParamKeys.contains(key) && key != _commentJsonKey) {
errorString = _loadErrorString(QString("Unknown param key: %1").arg(key));
return false;
}
}
// Validate key types
QList<QJsonValue::Type> types;
types << QJsonValue::Double << QJsonValue::Double << QJsonValue::String << QJsonValue::String << QJsonValue::String << QJsonValue::String;
if (!JsonHelper::validateKeyTypes(jsonObject, allParamKeys, types, internalError)) {
errorString = _loadErrorString(internalError);
return false;
}
_setInfoValue(_friendlyEditJsonKey, true); // Assume friendly edit if we have params
if (!paramObject.contains(_labelJsonKey)) {
internalError = QString("param object missing label key: %1").arg(paramKey);
errorString = _loadErrorString(internalError);
return false;
}
MissionCmdParamInfo* paramInfo = new MissionCmdParamInfo(this);
paramInfo->_label = paramObject.value(_labelJsonKey).toString();
paramInfo->_defaultValue = paramObject.value(_defaultJsonKey).toDouble(0.0);
paramInfo->_decimalPlaces = paramObject.value(_decimalPlacesJsonKey).toInt(FactMetaData::unknownDecimalPlaces);
paramInfo->_enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
paramInfo->_param = i;
paramInfo->_units = paramObject.value(_unitsJsonKey).toString();
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
foreach (const QString &enumValue, enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);
if (!convertOk) {
internalError = QString("Bad enumValue: %1").arg(enumValue);
errorString = _loadErrorString(internalError);
return false;
}
paramInfo->_enumValues << QVariant(value);
}
if (paramInfo->_enumValues.count() != paramInfo->_enumStrings.count()) {
internalError = QString("enum strings/values count mismatch: %1, %2").arg(paramInfo->_enumStrings.count()).arg(paramInfo->_enumValues.count());
errorString = _loadErrorString(internalError);
return false;
}
qCDebug(MissionCommandsLog) << "Param"
<< paramInfo->_label
<< paramInfo->_defaultValue
<< paramInfo->_decimalPlaces
<< paramInfo->_param
<< paramInfo->_units
<< paramInfo->_enumStrings
<< paramInfo->_enumValues;
_paramInfoMap[i] = paramInfo;
}
}
return true;
}
const MissionCmdParamInfo* MissionCommandUIInfo::getParamInfo(int index) const
{
if (!_paramRemoveList.contains(index) && _paramInfoMap.contains(index)) {
return _paramInfoMap[index];
} else {
return NULL;
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef MissionCommandUIInfo_H
#define MissionCommandUIInfo_H
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include <QString>
#include <QVariant>
class MissionCommandTree;
class MissionCommandUIInfo;
#ifdef UNITTEST_BUILD
class MissionCommandTreeTest;
#endif
/// UI Information associated with a mission command (MAV_CMD) parameter
///
/// MissionCommandParamInfo is used to automatically generate editing ui for a parameter assocaited with a MAV_CMD.
///
/// The json format for a MissionCmdParamInfo object is:
///
/// Key Type Default Description
/// label string required Label for text field
/// units string Units for value, should use FactMetaData units strings in order to get automatic translation
/// default double 0.0 Default value for param
/// decimalPlaces int 7 Number of decimal places to show for value
/// enumStrings string Strings to show in combo box for selection
/// enumValues string Values assocaited with each enum string
///
class MissionCmdParamInfo : public QObject {
Q_OBJECT
public:
MissionCmdParamInfo(QObject* parent = NULL);
MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent = NULL);
const MissionCmdParamInfo& operator=(const MissionCmdParamInfo& other);
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
Q_PROPERTY(double defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(QStringList enumStrings READ enumStrings CONSTANT)
Q_PROPERTY(QVariantList enumValues READ enumValues CONSTANT)
Q_PROPERTY(QString label READ label CONSTANT)
Q_PROPERTY(int param READ param CONSTANT)
Q_PROPERTY(QString units READ units CONSTANT)
int decimalPlaces (void) const { return _decimalPlaces; }
double defaultValue (void) const { return _defaultValue; }
QStringList enumStrings (void) const { return _enumStrings; }
QVariantList enumValues (void) const { return _enumValues; }
QString label (void) const { return _label; }
int param (void) const { return _param; }
QString units (void) const { return _units; }
private:
int _decimalPlaces;
double _defaultValue;
QStringList _enumStrings;
QVariantList _enumValues;
QString _label;
int _param;
QString _units;
friend class MissionCommandTree;
friend class MissionCommandUIInfo;
};
/// UI Information associated with a mission command (MAV_CMD)
///
/// MissionCommandUIInfo is used to automatically generate editing ui for a MAV_CMD. This object also supports the concept of only having a set of partial
/// information for the command. This is used to create overrides of the base command information. For on override just specify the keys you want to modify
/// from the base command ui info. To override param ui info you must specify the entire MissionParamInfo object.
///
/// The json format for a MissionCommandUIInfo object is:
///
/// Key Type Default Description
/// id int reauired MAV_CMD id
/// comment string Used to add a comment
/// rawName string required MAV_CMD enum name, should only be set of base tree information
/// friendlyName string rawName Short description of command
/// description string Long description of command
/// specifiesCoordinate bool false true: Command specifies a lat/lon/alt coordinate
/// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI)
/// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only
/// category string Advanced Category which this command belongs to
/// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override
/// param[1-7] object MissionCommandParamInfo object
///
class MissionCommandUIInfo : public QObject {
Q_OBJECT
public:
MissionCommandUIInfo(QObject* parent = NULL);
MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent = NULL);
const MissionCommandUIInfo& operator=(const MissionCommandUIInfo& other);
Q_PROPERTY(QString category READ category CONSTANT)
Q_PROPERTY(QString description READ description CONSTANT)
Q_PROPERTY(bool friendlyEdit READ friendlyEdit CONSTANT)
Q_PROPERTY(QString friendlyName READ friendlyName CONSTANT)
Q_PROPERTY(QString rawName READ rawName CONSTANT)
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
Q_PROPERTY(int command READ intCommand CONSTANT)
MAV_CMD command(void) const { return _command; }
int intCommand(void) const { return (int)_command; }
QString category (void) const;
QString description (void) const;
bool friendlyEdit (void) const;
QString friendlyName (void) const;
QString rawName (void) const;
bool isStandaloneCoordinate (void) const;
bool specifiesCoordinate (void) const;
/// Load the data in the object from the specified json
/// @param jsonObject Json object to load from
/// @param requireFullObject true: not a partial load, false: partial load allowed
/// @return true: success, false: failure, errorString set
bool loadJsonInfo(const QJsonObject& jsonObject, bool requireFullObject, QString& errorString);
/// Return param info for index, NULL for param should not be shown
const MissionCmdParamInfo* getParamInfo(int index) const;
private:
QString _loadErrorString(const QString& errorString) const;
/// Returns whether the specific information value is available
bool _infoAvailable(const QString& key) const { return _infoMap.contains(key); }
/// Returns the values for the specified value
const QVariant _infoValue(const QString& key) const { return _infoMap[key]; }
/// Set the value for the specified piece of information
void _setInfoValue(const QString& key, const QVariant& value) { _infoMap[key] = value; }
/// Overrides the existing values with new ui info
/// @param uiInfo New ui info to override existing info
void _overrideInfo(MissionCommandUIInfo* uiInfo);
MAV_CMD _command;
QMap<QString, QVariant> _infoMap;
QMap<int, MissionCmdParamInfo*> _paramInfoMap;
QList<int> _paramRemoveList;
static const char* _categoryJsonKey;
static const char* _decimalPlacesJsonKey;
static const char* _defaultJsonKey;
static const char* _descriptionJsonKey;
static const char* _enumStringsJsonKey;
static const char* _enumValuesJsonKey;
static const char* _friendlyNameJsonKey;
static const char* _friendlyEditJsonKey;
static const char* _idJsonKey;
static const char* _labelJsonKey;
static const char* _mavCmdInfoJsonKey;
static const char* _param1JsonKey;
static const char* _param2JsonKey;
static const char* _param3JsonKey;
static const char* _param4JsonKey;
static const char* _param5JsonKey;
static const char* _param6JsonKey;
static const char* _param7JsonKey;
static const char* _paramJsonKeyFormat;
static const char* _paramRemoveJsonKey;
static const char* _rawNameJsonKey;
static const char* _standaloneCoordinateJsonKey;
static const char* _specifiesCoordinateJsonKey;
static const char* _unitsJsonKey;
static const char* _commentJsonKey;
static const char* _advancedCategory;
friend class MissionCommandTree;
#ifdef UNITTEST_BUILD
friend class MissionCommandTreeTest;
#endif
};
#endif
/****************************************************************************
*
* (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 "MissionCommands.h"
#include "FactMetaData.h"
#include "Vehicle.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include <QQmlEngine>
MissionCommands::MissionCommands(QGCApplication* app)
: QGCTool(app)
, _commonMissionCommands(QStringLiteral(":/json/MavCmdInfoCommon.json"))
{
}
void MissionCommands::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
// Setup overrides
QString overrideCommonJsonFilename;
QString overrideFixedWingJsonFilename;
QString overrideMultiRotorJsonFilename;
QList<MAV_AUTOPILOT> firmwareList;
firmwareList << MAV_AUTOPILOT_GENERIC << MAV_AUTOPILOT_PX4 << MAV_AUTOPILOT_ARDUPILOTMEGA;
foreach (MAV_AUTOPILOT firmwareType, firmwareList) {
FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
plugin->missionCommandOverrides(overrideCommonJsonFilename, overrideFixedWingJsonFilename, overrideMultiRotorJsonFilename);
_autopilotToCommonMissionCommands[firmwareType] = new MissionCommandList(overrideCommonJsonFilename);
_autopilotToFixedWingMissionCommands[firmwareType] = new MissionCommandList(overrideFixedWingJsonFilename);
_autopilotToMultiRotorMissionCommands[firmwareType] = new MissionCommandList(overrideMultiRotorJsonFilename);
}
_createCategories();
}
/// Create category hierarchy for support commands
void MissionCommands::_createCategories(void)
{
// FIXME: This isn't quite right since it's hardcoding the firmware providers. But ok for now.
QList<MAV_AUTOPILOT> firmwareList;
firmwareList << MAV_AUTOPILOT_GENERIC << MAV_AUTOPILOT_PX4 << MAV_AUTOPILOT_ARDUPILOTMEGA;
foreach (MAV_AUTOPILOT firmwareType, firmwareList) {
FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
bool allCommandsSupported = false;
QList<MAV_CMD> cmdList = plugin->supportedMissionCommands();
if (cmdList.isEmpty()) {
allCommandsSupported = true;
cmdList = _commonMissionCommands.commandsIds();
}
foreach (MAV_CMD command, cmdList) {
MavCmdInfo* mavCmdInfo = _commonMissionCommands.getMavCmdInfo(command);
if (mavCmdInfo) {
if (mavCmdInfo->friendlyEdit()) {
_categoryToMavCmdListMap[firmwareType][mavCmdInfo->category()].append(command);
} else if (!allCommandsSupported) {
qWarning() << "Attempt to add non friendly edit supported command" << command;
}
} else {
qCDebug(MissionCommandsLog) << "Command missing from json" << command;
}
}
}
}
MAV_AUTOPILOT MissionCommands::_firmwareTypeFromVehicle(Vehicle* vehicle) const
{
if (vehicle) {
return vehicle->firmwareType();
} else {
return (MAV_AUTOPILOT)QGroundControlQmlGlobal::offlineEditingFirmwareType()->rawValue().toInt();
}
}
QString MissionCommands::categoryFromCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) const
{
return _commonMissionCommands.getMavCmdInfo((MAV_CMD)command)->category();
}
QVariant MissionCommands::getCommandsForCategory(Vehicle* vehicle, const QString& category) const
{
QmlObjectListModel* list = new QmlObjectListModel();
QQmlEngine::setObjectOwnership(list, QQmlEngine::JavaScriptOwnership);
foreach (MAV_CMD command, _categoryToMavCmdListMap[_firmwareTypeFromVehicle(vehicle)][category]) {
list->append(getMavCmdInfo(command, vehicle));
}
return QVariant::fromValue(list);
}
const QStringList MissionCommands::categories(Vehicle* vehicle) const
{
QStringList list;
foreach (const QString &category, _categoryToMavCmdListMap[_firmwareTypeFromVehicle(vehicle)].keys()) {
list << category;
}
return list;
}
bool MissionCommands::contains(MAV_CMD command) const
{
return _commonMissionCommands.contains(command);
}
MavCmdInfo* MissionCommands::getMavCmdInfo(MAV_CMD command, Vehicle* vehicle) const
{
if (!contains(command)) {
qWarning() << "Unknown command" << command;
return NULL;
}
MavCmdInfo* mavCmdInfo = NULL;
MAV_AUTOPILOT firmwareType = _firmwareTypeFromVehicle(vehicle);
if (vehicle) {
if (vehicle->fixedWing()) {
if (_autopilotToFixedWingMissionCommands.contains(firmwareType) && _autopilotToFixedWingMissionCommands[firmwareType]->contains(command)) {
mavCmdInfo = _autopilotToFixedWingMissionCommands[firmwareType]->getMavCmdInfo(command);
}
} else if (vehicle->multiRotor()) {
if (_autopilotToMultiRotorMissionCommands.contains(firmwareType) && _autopilotToMultiRotorMissionCommands[firmwareType]->contains(command)) {
mavCmdInfo = _autopilotToMultiRotorMissionCommands[firmwareType]->getMavCmdInfo(command);
}
}
}
if (!mavCmdInfo && _autopilotToCommonMissionCommands.contains(firmwareType) && _autopilotToCommonMissionCommands[firmwareType]->contains(command)) {
mavCmdInfo = _autopilotToCommonMissionCommands[firmwareType]->getMavCmdInfo(command);
}
if (!mavCmdInfo) {
mavCmdInfo = _commonMissionCommands.getMavCmdInfo(command);
}
return mavCmdInfo;
}
QList<MAV_CMD> MissionCommands::commandsIds(void) const
{
return _commonMissionCommands.commandsIds();
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef MissionCommands_H
#define MissionCommands_H
#include "QGCToolbox.h"
#include "MissionCommandList.h"
/// Provides access to mission command information used for creating mission command ui editors. There is a base common set
/// of definitions. Individual commands can then be overriden depending on Vehicle information:
/// Common command definitions
/// MAV_AUTOPILOT common overrides
/// Fixed Wing
/// MAV_AUTOPILOT specific Fixed Wing overrides
/// Multi-Rotor
/// MAV_AUTOPILOT specific Multi Rotor overrides
/// The leaf nodes of the hierarchy take precedence over higher level branches
class MissionCommands : public QGCTool
{
Q_OBJECT
public:
MissionCommands(QGCApplication* app);
Q_INVOKABLE const QStringList categories (Vehicle* vehicle) const;
Q_INVOKABLE QString categoryFromCommand (MavlinkQmlSingleton::Qml_MAV_CMD command) const;
Q_INVOKABLE QVariant getCommandsForCategory (Vehicle* vehicle, const QString& category) const;
Q_INVOKABLE bool contains(MavlinkQmlSingleton::Qml_MAV_CMD command) const { return contains((MAV_CMD)command); }
bool contains(MAV_CMD command) const;
Q_INVOKABLE QVariant getMavCmdInfo(MavlinkQmlSingleton::Qml_MAV_CMD command, Vehicle* vehicle) const { return QVariant::fromValue(getMavCmdInfo((MAV_CMD)command, vehicle)); }
MavCmdInfo* getMavCmdInfo(MAV_CMD command, Vehicle* vehicle) const;
QList<MAV_CMD> commandsIds(void) const;
// Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox);
private:
void _createCategories(void);
MAV_AUTOPILOT _firmwareTypeFromVehicle(Vehicle* vehicle) const;
private:
QMap<MAV_AUTOPILOT, QMap<QString, QList<MAV_CMD> > > _categoryToMavCmdListMap;
MissionCommandList _commonMissionCommands; ///< Mission command definitions for common generic mavlink use case
QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToCommonMissionCommands; ///< MAV_AUTOPILOT specific common overrides
QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToFixedWingMissionCommands; ///< MAV_AUTOPILOT specific fixed wing overrides
QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToMultiRotorMissionCommands; ///< MAV_AUTOPILOT specific multi rotor overrides
};
#endif
......@@ -25,7 +25,6 @@
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
class ComplexMissionItem;
class SimpleMissionItem;
......
......@@ -15,8 +15,10 @@
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
const double SimpleMissionItem::defaultAltitude = 25.0;
const double SimpleMissionItem::defaultAltitude = 50.0;
FactMetaData* SimpleMissionItem::_altitudeMetaData = NULL;
FactMetaData* SimpleMissionItem::_commandMetaData = NULL;
......@@ -50,6 +52,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
, _rawEdit(false)
, _homePositionSpecialCase(false)
, _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _param1MetaData(FactMetaData::valueTypeDouble)
......@@ -61,7 +64,6 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
, _param7MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
_altitudeRelativeToHomeFact.setRawValue(true);
......@@ -78,6 +80,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
, _dirty(false)
, _homePositionSpecialCase(false)
, _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _param1MetaData(FactMetaData::valueTypeDouble)
......@@ -89,7 +92,6 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
, _param7MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
_altitudeRelativeToHomeFact.setRawValue(true);
......@@ -106,6 +108,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
, _dirty(false)
, _homePositionSpecialCase(false)
, _showHomePosition(false)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _param1MetaData(FactMetaData::valueTypeDouble)
......@@ -114,7 +117,6 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
, _param4MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
_setupMetaData();
_connectSignals();
......@@ -197,10 +199,10 @@ void SimpleMissionItem::_setupMetaData(void)
enumStrings.clear();
enumValues.clear();
foreach (const MAV_CMD command, _missionCommands->commandsIds()) {
const MavCmdInfo* mavCmdInfo = _missionCommands->getMavCmdInfo(command, _vehicle);
enumStrings.append(mavCmdInfo->rawName());
enumValues.append(QVariant(mavCmdInfo->command()));
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
foreach (const MAV_CMD command, commandTree->allCommandIds()) {
enumStrings.append(commandTree->rawName(command));
enumValues.append(QVariant((int)command));
}
_commandMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
_commandMetaData->setEnumInfo(enumStrings, enumValues);
......@@ -254,8 +256,9 @@ bool SimpleMissionItem::load(const QJsonObject& json, QString& errorString)
bool SimpleMissionItem::isStandaloneCoordinate(void) const
{
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->isStandaloneCoordinate();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo) {
return uiInfo->isStandaloneCoordinate();
} else {
return false;
}
......@@ -263,8 +266,9 @@ bool SimpleMissionItem::isStandaloneCoordinate(void) const
bool SimpleMissionItem::specifiesCoordinate(void) const
{
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->specifiesCoordinate();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo) {
return uiInfo->specifiesCoordinate();
} else {
return false;
}
......@@ -272,8 +276,9 @@ bool SimpleMissionItem::specifiesCoordinate(void) const
QString SimpleMissionItem::commandDescription(void) const
{
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->description();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo) {
return uiInfo->description();
} else {
qWarning() << "Should not ask for command description on unknown command";
return commandName();
......@@ -282,13 +287,12 @@ QString SimpleMissionItem::commandDescription(void) const
QString SimpleMissionItem::commandName(void) const
{
MAV_CMD command = (MAV_CMD)this->command();
if (_missionCommands->contains(command)) {
const MavCmdInfo* mavCmdInfo = _missionCommands->getMavCmdInfo(command, _vehicle);
return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo) {
return uiInfo->friendlyName();
} else {
qWarning() << "Request for command name on unknown command";
return QString("Unknown: %1").arg(command);
return tr("Unknown: %1").arg(command());
}
}
......@@ -364,12 +368,11 @@ QmlObjectListModel* SimpleMissionItem::textFieldFacts(void)
bool altitudeAdded = false;
for (int i=1; i<=7; i++) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap();
const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_vehicle, command)->getParamInfo(i);
if (paramInfoMap.contains(i) && paramInfoMap[i]->enumStrings().count() == 0) {
if (paramInfo && paramInfo->enumStrings().count() == 0) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];
MavCmdParamInfo* paramInfo = paramInfoMap[i];
paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
......@@ -428,12 +431,11 @@ QmlObjectListModel* SimpleMissionItem::comboboxFacts(void)
}
for (int i=1; i<=7; i++) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap();
const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_vehicle, command)->getParamInfo(i);
if (paramInfoMap.contains(i) && paramInfoMap[i]->enumStrings().count() != 0) {
if (paramInfo && paramInfo->enumStrings().count() != 0) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];
MavCmdParamInfo* paramInfo = paramInfoMap[i];
paramFact->_setName(paramInfo->label());
paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
......@@ -450,7 +452,8 @@ QmlObjectListModel* SimpleMissionItem::comboboxFacts(void)
bool SimpleMissionItem::friendlyEditAllowed(void) const
{
if (_missionCommands->contains((MAV_CMD)command()) && _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->friendlyEdit()) {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo && uiInfo->friendlyEdit()) {
if (!_missionItem.autoContinue()) {
return false;
}
......@@ -524,12 +527,14 @@ void SimpleMissionItem::setDefaultsForCommand(void)
_missionItem.setParam7(defaultAltitude);
MAV_CMD command = (MAV_CMD)this->command();
if (_missionCommands->contains(command)) {
MavCmdInfo* mavCmdInfo = _missionCommands->getMavCmdInfo(command, _vehicle);
foreach (const MavCmdParamInfo* paramInfo, mavCmdInfo->paramInfoMap()) {
Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
if (uiInfo) {
for (int i=1; i<=7; i++) {
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i);
if (paramInfo) {
Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
}
}
}
......@@ -566,7 +571,7 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
QString SimpleMissionItem::category(void) const
{
return qgcApp()->toolbox()->missionCommands()->categoryFromCommand(command());
return _commandTree->getUIInfo(_vehicle, (MAV_CMD)command())->category();
}
void SimpleMissionItem::setShowHomePosition(bool showHomePosition)
......
......@@ -13,6 +13,7 @@
#include "VisualMissionItem.h"
#include "MissionItem.h"
#include "MissionCommandTree.h"
/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
class SimpleMissionItem : public VisualMissionItem
......@@ -134,6 +135,8 @@ private:
bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator
bool _showHomePosition;
MissionCommandTree* _commandTree;
Fact _altitudeRelativeToHomeFact;
Fact _supportedCommandFact;
......@@ -154,8 +157,6 @@ private:
bool _syncingAltitudeRelativeToHomeAndFrame; ///< true: already in a sync signal, prevents signal loop
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
const MissionCommands* _missionCommands;
};
#endif
{
"comment": "Any Firmware, Any Vehicle (unit test)",
"version": 1,
"mavCmdInfo": [
{
"comment": "Check defaults",
"id": 1,
"rawName": "UNITTEST_1"
},
{
"comment": "Check param defaults",
"id": 2,
"rawName": "UNITTEST_2",
"param1": {
"label": "param1"
}
},
{
"comment": "Check all values",
"id": 3,
"rawName": "UNITTEST_3",
"friendlyName": "Unit Test 3",
"description": "description",
"specifiesCoordinate": true,
"standaloneCoordinate": true,
"friendlyEdit": true,
"category": "category",
"param1": {
"label": "param1",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param2": {
"label": "param2",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param3": {
"label": "param3",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param4": {
"label": "param4",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param5": {
"label": "param5",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param6": {
"label": "param6",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param7": {
"label": "param7",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
}
},
{
"comment": "Full values set for override testing",
"id": 4,
"rawName": "UNITTEST_4",
"friendlyName": "Unit Test 4",
"description": "description",
"specifiesCoordinate": true,
"standaloneCoordinate": true,
"friendlyEdit": true,
"category": "category",
"param1": {
"label": "param1",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param2": {
"label": "param2",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param3": {
"label": "param3",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param4": {
"label": "param4",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param5": {
"label": "param5",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param6": {
"label": "param6",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param7": {
"label": "param7",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
}
},
{
"comment": "Full values set for override testing",
"id": 5,
"rawName": "UNITTEST_5",
"friendlyName": "Unit Test 5",
"description": "description",
"specifiesCoordinate": true,
"standaloneCoordinate": true,
"friendlyEdit": true,
"category": "category",
"param1": {
"label": "param1",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param2": {
"label": "param2",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param3": {
"label": "param3",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param4": {
"label": "param4",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param5": {
"label": "param5",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param6": {
"label": "param6",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
},
"param7": {
"label": "param7",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "units"
}
}
]
}
{
"comment": "Any Firmware, Fixed Wing (unit test)",
"version": 1,
"mavCmdInfo": [
{
"comment": "Override testing",
"id": 4,
"description": "override fw 4",
"specifiesCoordinate": false,
"standaloneCoordinate": false,
"friendlyEdit": true,
"category": "override fw 4",
"paramRemove": "2,4,6",
"param1": {
"label": "override fw 4 1",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "override fw 4 1"
},
"param3": {
"label": "override fw 4 3",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "override fw 4 3"
},
"param5": {
"label": "override fw 4 5",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "override fw 4 5"
},
"param7": {
"label": "override fw 4 7",
"default": 1.0,
"decimalPlaces": 1,
"enumStrings": "1,2",
"enumValues": "1,2",
"units": "override fw 4 7"
}
}
]
}
{
"comment": "Any Firmware, Multi Rotor (unit test)",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, Rover (unit test)",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, Sub (unit test)",
"version": 1,
"mavCmdInfo": [
]
}
{
"comment": "Any Firmware, VTOL (unit test)",
"version": 1,
"mavCmdInfo": [
]
}
......@@ -25,7 +25,7 @@
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
#include "Vehicle.h"
// Abstract base class for all Simple and Complex visual mission objects.
class VisualMissionItem : public QObject
......
......@@ -82,7 +82,6 @@
#include "CoordinateVector.h"
#include "MainToolBarController.h"
#include "MissionController.h"
#include "MissionCommands.h"
#include "FlightDisplayViewController.h"
#include "VideoSurface.h"
#include "VideoReceiver.h"
......@@ -93,6 +92,7 @@
#include "SimulatedPosition.h"
#include "PositionManager.h"
#include "FollowMe.h"
#include "MissionCommandTree.h"
#ifndef __ios__
#include "SerialLink.h"
......@@ -365,10 +365,10 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<QGCMapPalette> ("QGroundControl.Palette", 1, 0, "QGCMapPalette");
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<MissionCommands> ("QGroundControl", 1, 0, "MissionCommands", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterUncreatableType<VideoReceiver> ("QGroundControl", 1, 0, "VideoReceiver", "Reference only");
qmlRegisterUncreatableType<VideoSurface> ("QGroundControl", 1, 0, "VideoSurface", "Reference only");
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", "Reference only");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Reference only");
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Reference only");
......
......@@ -20,7 +20,7 @@
#include "JoystickManager.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MissionCommands.h"
#include "MissionCommandTree.h"
#include "MultiVehicleManager.h"
#include "QGCImageProvider.h"
#include "UASMessageHandler.h"
......@@ -42,7 +42,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
, _joystickManager(NULL)
, _linkManager(NULL)
, _mavlinkProtocol(NULL)
, _missionCommands(NULL)
, _missionCommandTree(NULL)
, _multiVehicleManager(NULL)
, _mapEngineManager(NULL)
, _uasMessageHandler(NULL)
......@@ -62,7 +62,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_joystickManager = new JoystickManager(app);
_linkManager = new LinkManager(app);
_mavlinkProtocol = new MAVLinkProtocol(app);
_missionCommands = new MissionCommands(app);
_missionCommandTree = new MissionCommandTree(app);
_multiVehicleManager = new MultiVehicleManager(app);
_mapEngineManager = new QGCMapEngineManager(app);
_uasMessageHandler = new UASMessageHandler(app);
......@@ -82,7 +82,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_joystickManager->setToolbox(this);
_linkManager->setToolbox(this);
_mavlinkProtocol->setToolbox(this);
_missionCommands->setToolbox(this);
_missionCommandTree->setToolbox(this);
_multiVehicleManager->setToolbox(this);
_mapEngineManager->setToolbox(this);
_uasMessageHandler->setToolbox(this);
......@@ -101,7 +101,7 @@ QGCToolbox::~QGCToolbox()
delete _joystickManager;
delete _linkManager;
delete _mavlinkProtocol;
delete _missionCommands;
delete _missionCommandTree;
delete _mapEngineManager;
delete _multiVehicleManager;
delete _uasMessageHandler;
......
......@@ -24,7 +24,7 @@ class JoystickManager;
class FollowMe;
class LinkManager;
class MAVLinkProtocol;
class MissionCommands;
class MissionCommandTree;
class MultiVehicleManager;
class QGCMapEngineManager;
class QGCApplication;
......@@ -47,7 +47,7 @@ public:
JoystickManager* joystickManager(void) { return _joystickManager; }
LinkManager* linkManager(void) { return _linkManager; }
MAVLinkProtocol* mavlinkProtocol(void) { return _mavlinkProtocol; }
MissionCommands* missionCommands(void) { return _missionCommands; }
MissionCommandTree* missionCommandTree(void) { return _missionCommandTree; }
MultiVehicleManager* multiVehicleManager(void) { return _multiVehicleManager; }
QGCMapEngineManager* mapEngineManager(void) { return _mapEngineManager; }
QGCImageProvider* imageProvider() { return _imageProvider; }
......@@ -72,7 +72,7 @@ private:
JoystickManager* _joystickManager;
LinkManager* _linkManager;
MAVLinkProtocol* _mavlinkProtocol;
MissionCommands* _missionCommands;
MissionCommandTree* _missionCommandTree;
MultiVehicleManager* _multiVehicleManager;
QGCMapEngineManager* _mapEngineManager;
UASMessageHandler* _uasMessageHandler;
......
......@@ -36,10 +36,10 @@ QGCViewDialog {
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: categoryLabel.right
anchors.right: parent.right
model: QGroundControl.missionCommands.categories(_vehicle)
model: QGroundControl.missionCommandTree.categoriesForVehicle(_vehicle)
function categorySelected(category) {
commandList.model = QGroundControl.missionCommands.getCommandsForCategory(_vehicle, category)
commandList.model = QGroundControl.missionCommandTree.getCommandsForCategory(_vehicle, category)
}
Component.onCompleted: {
......@@ -67,7 +67,7 @@ QGCViewDialog {
height: commandColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.button
property var mavCmdInfo: object
property var mavCmdInfo: modelData
property var textColor: qgcPal.buttonText
Column {
......
......@@ -40,9 +40,10 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
, _flightMapSettings(NULL)
, _homePositionManager(NULL)
, _linkManager(NULL)
, _missionCommands(NULL)
, _multiVehicleManager(NULL)
, _mapEngineManager(NULL)
, _qgcPositionManager(NULL)
, _missionCommandTree(NULL)
, _virtualTabletJoystick(false)
, _baseFontPointSize(0.0)
{
......@@ -66,10 +67,10 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_flightMapSettings = toolbox->flightMapSettings();
_homePositionManager = toolbox->homePositionManager();
_linkManager = toolbox->linkManager();
_missionCommands = toolbox->missionCommands();
_multiVehicleManager = toolbox->multiVehicleManager();
_mapEngineManager = toolbox->mapEngineManager();
_qgcPositionManager = toolbox->qgcPositionManager();
_qgcPositionManager = toolbox->qgcPositionManager();
_missionCommandTree = toolbox->missionCommandTree();
}
......@@ -233,7 +234,7 @@ Fact* QGroundControlQmlGlobal::offlineEditingFirmwareType(void)
_offlineEditingFirmwareTypeFact = new SettingsFact(QString(), "OfflineEditingFirmwareType", FactMetaData::valueTypeUint32, (uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA);
_offlineEditingFirmwareTypeMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
enumStrings << "ArduPilot Firmware" << "PX4 Firmware" << "Mavlink Generic Firmware";
enumStrings << tr("ArduPilot Firmware") << tr("PX4 Pro Firmware") << tr("Mavlink Generic Firmware");
enumValues << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_PX4) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_GENERIC);
_offlineEditingFirmwareTypeMetaData->setEnumInfo(enumStrings, enumValues);
......@@ -252,8 +253,10 @@ Fact* QGroundControlQmlGlobal::offlineEditingVehicleType(void)
_offlineEditingVehicleTypeFact = new SettingsFact(QString(), "OfflineEditingVehicleType", FactMetaData::valueTypeUint32, (uint32_t)MAV_TYPE_FIXED_WING);
_offlineEditingVehicleTypeMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
enumStrings << "Fixedwing" << "Multicopter" << "VTOL";
enumValues << QVariant::fromValue((uint32_t)MAV_TYPE_FIXED_WING) << QVariant::fromValue((uint32_t)MAV_TYPE_QUADROTOR) << QVariant::fromValue((uint32_t)MAV_TYPE_VTOL_DUOROTOR);
enumStrings << tr("Fixedwing") << tr("Multicopter") << tr("VTOL") << tr("Rover") << tr("Sub");
enumValues << QVariant::fromValue((uint32_t)MAV_TYPE_FIXED_WING) << QVariant::fromValue((uint32_t)MAV_TYPE_QUADROTOR)
<< QVariant::fromValue((uint32_t)MAV_TYPE_VTOL_DUOROTOR) << QVariant::fromValue((uint32_t)MAV_TYPE_GROUND_ROVER)
<< QVariant::fromValue((uint32_t)MAV_TYPE_SUBMARINE);
_offlineEditingVehicleTypeMetaData->setEnumInfo(enumStrings, enumValues);
_offlineEditingVehicleTypeFact->setMetaData(_offlineEditingVehicleTypeMetaData);
......
......@@ -19,7 +19,6 @@
#include "LinkManager.h"
#include "HomePositionManager.h"
#include "FlightMapSettings.h"
#include "MissionCommands.h"
#include "SettingsFact.h"
#include "FactMetaData.h"
#include "SimulatedPosition.h"
......@@ -68,10 +67,10 @@ public:
Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT)
Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT)
Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT)
Q_PROPERTY(MissionCommands* missionCommands READ missionCommands CONSTANT)
Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT)
Q_PROPERTY(QGCMapEngineManager* mapEngineManager READ mapEngineManager CONSTANT)
Q_PROPERTY(QGCPositionManager* qgcPositionManger READ qgcPositionManger CONSTANT)
Q_PROPERTY(MissionCommandTree* missionCommandTree READ missionCommandTree CONSTANT)
Q_PROPERTY(qreal zOrderTopMost READ zOrderTopMost CONSTANT) ///< z order for top most items, toolbar, main window sub view
Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
......@@ -161,10 +160,10 @@ public:
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
HomePositionManager* homePositionManager () { return _homePositionManager; }
LinkManager* linkManager () { return _linkManager; }
MissionCommands* missionCommands () { return _missionCommands; }
MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; }
QGCPositionManager* qgcPositionManger () { return _qgcPositionManager; }
MissionCommandTree* missionCommandTree () { return _missionCommandTree; }
qreal zOrderTopMost () { return 1000; }
qreal zOrderWidgets () { return 100; }
......@@ -229,10 +228,10 @@ private:
FlightMapSettings* _flightMapSettings;
HomePositionManager* _homePositionManager;
LinkManager* _linkManager;
MissionCommands* _missionCommands;
MultiVehicleManager* _multiVehicleManager;
QGCMapEngineManager* _mapEngineManager;
QGCPositionManager* _qgcPositionManager;
MissionCommandTree* _missionCommandTree;
bool _virtualTabletJoystick;
qreal _baseFontPointSize;
......
......@@ -51,7 +51,7 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app)
_gcsHeartbeatTimer.start();
}
_disconnectedVehicle = new Vehicle(this);
_disconnectedVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, this);
}
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
......
......@@ -45,7 +45,7 @@ public:
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles CONSTANT)
Q_PROPERTY(bool gcsHeartBeatEnabled READ gcsHeartbeatEnabled WRITE setGcsHeartbeatEnabled NOTIFY gcsHeartBeatEnabledChanged)
/// A disconnected vehicle is used to access FactGroup information for the Vehicle object when no active vehicle is available
/// A disconnected vehicle is used to simulate vehicle information while no vehicle is connected.
Q_PROPERTY(Vehicle* disconnectedVehicle MEMBER _disconnectedVehicle CONSTANT)
// Methods
......
......@@ -23,6 +23,7 @@
#include "QGCImageProvider.h"
#include "GAudioOutput.h"
#include "FollowMe.h"
#include "MissionCommandTree.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
......@@ -245,13 +246,13 @@ Vehicle::Vehicle(LinkInterface* link,
}
// Disconnected Vehicle
Vehicle::Vehicle(QObject* parent)
Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
, _id(0)
, _active(false)
, _disconnectedVehicle(false)
, _firmwareType(MAV_AUTOPILOT_PX4)
, _vehicleType(MAV_TYPE_QUADROTOR)
, _disconnectedVehicle(true)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
, _firmwarePlugin(NULL)
, _autopilotPlugin(NULL)
, _joystickMode(JoystickModeRC)
......@@ -312,6 +313,11 @@ Vehicle::Vehicle(QObject* parent)
, _windFactGroup(this)
, _vibrationFactGroup(this)
{
// This is a hack for disconnected vehicle used while unit testing
if (qgcApp()->toolbox() && qgcApp()->toolbox()->firmwarePluginManager()) {
_firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
}
// Build FactGroup object model
_addFact(&_rollFact, _rollFactName);
......@@ -488,13 +494,7 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
return;
}
QString commandName;
MavCmdInfo* cmdInfo = qgcApp()->toolbox()->missionCommands()->getMavCmdInfo((MAV_CMD)ack.command, this);
if (cmdInfo) {
commandName = cmdInfo->friendlyName();
} else {
commandName = tr("cmdid %1").arg(ack.command);
}
QString commandName = qgcApp()->toolbox()->missionCommandTree()->friendlyName((MAV_CMD)ack.command);
switch (ack.result) {
case MAV_RESULT_TEMPORARILY_REJECTED:
......@@ -1471,32 +1471,22 @@ void Vehicle::_say(const QString& text)
bool Vehicle::fixedWing(void) const
{
return vehicleType() == MAV_TYPE_FIXED_WING;
return QGCMAVLink::isFixedWing(vehicleType());
}
bool Vehicle::rover(void) const
{
return vehicleType() == MAV_TYPE_GROUND_ROVER;
return QGCMAVLink::isRover(vehicleType());
}
bool Vehicle::sub(void) const
{
return vehicleType() == MAV_TYPE_SUBMARINE;
return QGCMAVLink::isSub(vehicleType());
}
bool Vehicle::multiRotor(void) const
{
switch (vehicleType()) {
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
return true;
default:
return false;
}
return QGCMAVLink::isMultiRotor(vehicleType());
}
bool Vehicle::vtol(void) const
......
......@@ -225,9 +225,9 @@ public:
AutoPilotPluginManager* autopilotPluginManager,
JoystickManager* joystickManager);
// The following is used to create a disconnected Vehicle. A disconnected vehicle is primarily used to access FactGroup information
// without needing a real connection.
Vehicle(QObject* parent = NULL);
// The following is used to create a disconnected Vehicle. Disconnected vehicles are used used to access FactGroup information
// without needing a real connection as well as offline mission planning.
Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent = NULL);
~Vehicle();
......
......@@ -30,6 +30,7 @@
#include "FileManagerTest.h"
#include "TCPLinkTest.h"
#include "ParameterLoaderTest.h"
#include "MissionCommandTreeTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -48,6 +49,7 @@ UT_REGISTER_TEST(RadioConfigTest)
UT_REGISTER_TEST(TCPLinkTest)
UT_REGISTER_TEST(FileManagerTest)
UT_REGISTER_TEST(ParameterLoaderTest)
UT_REGISTER_TEST(MissionCommandTreeTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
......@@ -44,7 +44,6 @@
#include "Vehicle.h"
#include "Joystick.h"
#include "QGCApplication.h"
#include "MissionCommands.h"
QGC_LOGGING_CATEGORY(UASLog, "UASLog")
......
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