Commit 96995949 authored by Don Gagne's avatar Don Gagne

Support command editor overrides

- override by vehicle type
- override by firmware type
parent 8a049a99
...@@ -251,6 +251,7 @@ HEADERS += \ ...@@ -251,6 +251,7 @@ HEADERS += \
src/Joystick/JoystickManager.h \ src/Joystick/JoystickManager.h \
src/LogCompressor.h \ src/LogCompressor.h \
src/MG.h \ src/MG.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommands.h \ src/MissionManager/MissionCommands.h \
src/MissionManager/MissionController.h \ src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \ src/MissionManager/MissionItem.h \
...@@ -374,6 +375,7 @@ SOURCES += \ ...@@ -374,6 +375,7 @@ SOURCES += \
src/Joystick/JoystickManager.cc \ src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \ src/LogCompressor.cc \
src/main.cc \ src/main.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommands.cc \ src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionController.cc \ src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \ src/MissionManager/MissionItem.cc \
......
...@@ -141,6 +141,12 @@ ...@@ -141,6 +141,12 @@
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file> <file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
</qresource> </qresource>
<qresource prefix="/json"> <qresource prefix="/json">
<file alias="MavCmdInfo.json">src/MissionManager/MavCmdInfo.json</file> <file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.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="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>
</qresource> </qresource>
</RCC> </RCC>
...@@ -495,3 +495,10 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void) ...@@ -495,3 +495,10 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_CHANGE_ALT << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW; << MAV_CMD_CONDITION_DELAY << MAV_CMD_CONDITION_CHANGE_ALT << MAV_CMD_CONDITION_DISTANCE << MAV_CMD_CONDITION_YAW;
return list; return list;
} }
void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{
commonJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoCommon.json");
fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
}
...@@ -92,6 +92,7 @@ public: ...@@ -92,6 +92,7 @@ public:
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
virtual QList<MAV_CMD> supportedMissionCommands(void); virtual QList<MAV_CMD> supportedMissionCommands(void);
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
protected: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation
......
{
"version": 1,
"mavCmdInfo": [
]
}
{
"version": 1,
"mavCmdInfo": [
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Pitch:",
"units": "radians",
"default": 0.26179939,
"decimalPlaces": 2
}
}
]
}
{
"version": 1,
"mavCmdInfo": [
{
"id": 22,
"rawName": "MAV_CMD_NAV_TAKEOFF",
"friendlyName": "Takeoff",
"description": "Take off from the ground.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic"
},
{
"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": 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": "meters",
"default": 10.0,
"decimalPlaces": 2
}
},
{
"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": "seconds",
"default": 30,
"decimalPlaces": 0
}
}
]
}
...@@ -113,6 +113,12 @@ public: ...@@ -113,6 +113,12 @@ public:
/// List of supported mission commands. Empty list for all commands supported. /// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void) = 0; virtual QList<MAV_CMD> supportedMissionCommands(void) = 0;
/// 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 = 0;
}; };
#endif #endif
...@@ -127,3 +127,11 @@ QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void) ...@@ -127,3 +127,11 @@ QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
// Generic supports all commands // Generic supports all commands
return QList<MAV_CMD>(); return QList<MAV_CMD>();
} }
void GenericFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{
// No overrides
commonJsonFilename.clear();
fixedWingJsonFilename.clear();
multiRotorJsonFilename.clear();
}
...@@ -35,19 +35,19 @@ class GenericFirmwarePlugin : public FirmwarePlugin ...@@ -35,19 +35,19 @@ class GenericFirmwarePlugin : public FirmwarePlugin
public: public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
bool isCapable(FirmwareCapabilities capabilities) final { Q_UNUSED(capabilities); return false; }
virtual bool isCapable(FirmwareCapabilities capabilities) { Q_UNUSED(capabilities); return false; } QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle); QStringList flightModes(void) final { return QStringList(); }
virtual QStringList flightModes(void) { return QStringList(); } QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); int manualControlReservedButtonCount(void) final;
virtual int manualControlReservedButtonCount(void); void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); void initializeVehicle(Vehicle* vehicle) final;
virtual void initializeVehicle(Vehicle* vehicle); bool sendHomePositionToVehicle(void) final;
virtual bool sendHomePositionToVehicle(void); void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); QString getDefaultComponentIdParam(void) const final { return QString(); }
virtual QString getDefaultComponentIdParam(void) const { return QString(); } QList<MAV_CMD> supportedMissionCommands(void) final;
virtual QList<MAV_CMD> supportedMissionCommands(void); void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
}; };
#endif #endif
{
"version": 1,
"mavCmdInfo": [
]
}
{
"version": 1,
"mavCmdInfo": [
]
}
{
"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": 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": 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": "seconds",
"default": 30,
"decimalPlaces": 0
}
}
]
}
...@@ -225,3 +225,11 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) ...@@ -225,3 +225,11 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_DO_CHANGE_SPEED; << MAV_CMD_DO_CHANGE_SPEED;
return list; return list;
} }
void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{
// No overrides
commonJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoCommon.json");
fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
}
...@@ -36,18 +36,19 @@ class PX4FirmwarePlugin : public FirmwarePlugin ...@@ -36,18 +36,19 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public: public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
virtual bool isCapable(FirmwareCapabilities capabilities); bool isCapable(FirmwareCapabilities capabilities) final;
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle); QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
virtual QStringList flightModes(void); QStringList flightModes(void) final;
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
virtual int manualControlReservedButtonCount(void); int manualControlReservedButtonCount(void) final;
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
virtual void initializeVehicle(Vehicle* vehicle); void initializeVehicle(Vehicle* vehicle) final;
virtual bool sendHomePositionToVehicle(void); bool sendHomePositionToVehicle(void) final;
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } QString getDefaultComponentIdParam(void) const final { return QString("SYS_AUTOSTART"); }
virtual QList<MAV_CMD> supportedMissionCommands(void); QList<MAV_CMD> supportedMissionCommands(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
private: private:
PX4ParameterMetaData _parameterMetaData; PX4ParameterMetaData _parameterMetaData;
......
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionCommandList_H
#define MissionCommandList_H
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MavlinkQmlSingleton.h"
#include <QObject>
#include <QString>
#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)
{
}
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 standaloneCoordinate READ standaloneCoordinate 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 standaloneCoordinate(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.
class MissionCommandList : public QObject
{
Q_OBJECT
public:
MissionCommandList(const QString& jsonFilename, QObject* parent = NULL);
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) const { return QVariant::fromValue(getMavCmdInfo((MAV_CMD)command)); }
MavCmdInfo* getMavCmdInfo(MAV_CMD command) const;
QList<MAV_CMD> commandsIds(void) const;
private:
void _loadMavCmdInfoJson(const QString& jsonFilename);
bool _validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types);
private:
QMap<MAV_CMD, MavCmdInfo*> _mavCmdInfoMap;
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;
};
#endif
This diff is collapsed.
...@@ -25,104 +25,17 @@ ...@@ -25,104 +25,17 @@
#define MissionCommands_H #define MissionCommands_H
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "QGCMAVLink.h" #include "MissionCommandList.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h" /// Provides access to mission command information used for creating mission command ui editors. There is a base common set
#include "MavlinkQmlSingleton.h" /// of definitions. Individual commands can then be overriden depending on Vehicle information:
/// Common command definitions
#include <QObject> /// MAV_AUTOPILOT common overrides
#include <QString> /// Fixed Wing
#include <QJsonObject> /// MAV_AUTOPILOT specific Fixed Wing overrides
#include <QJsonValue> /// Multi-Rotor
/// MAV_AUTOPILOT specific Multi Rotor overrides
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog) /// The leaf nodes of the hierarchy take precedence over higher level branches
class MissionCommands;
class Vehicle;
class MavCmdParamInfo : public QObject {
Q_OBJECT
public:
MavCmdParamInfo(QObject* parent = NULL)
: QObject(parent)
{
}
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 MissionCommands;
};
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 command 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 standaloneCoordinate READ standaloneCoordinate CONSTANT)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
QString category (void) const { return _category; }
MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; }
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 standaloneCoordinate(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 MissionCommands;
};
class MissionCommands : public QGCTool class MissionCommands : public QGCTool
{ {
Q_OBJECT Q_OBJECT
...@@ -134,45 +47,29 @@ public: ...@@ -134,45 +47,29 @@ public:
Q_INVOKABLE QString categoryFromCommand (MavlinkQmlSingleton::Qml_MAV_CMD command) const; Q_INVOKABLE QString categoryFromCommand (MavlinkQmlSingleton::Qml_MAV_CMD command) const;
Q_INVOKABLE QVariant getCommandsForCategory (Vehicle* vehicle, const QString& category) const; Q_INVOKABLE QVariant getCommandsForCategory (Vehicle* vehicle, const QString& category) const;
const QMap<MAV_CMD, MavCmdInfo*>& commandInfoMap(void) const { return _mavCmdInfoMap; }; 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 // Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox); virtual void setToolbox(QGCToolbox* toolbox);
signals:
private: private:
void _loadMavCmdInfoJson(void); void _createCategories(void);
void _createFirmwareSpecificLists(void);
void _setupMetaData(void);
bool _validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types);
MAV_AUTOPILOT _firmwareTypeFromVehicle(Vehicle* vehicle) const; MAV_AUTOPILOT _firmwareTypeFromVehicle(Vehicle* vehicle) const;
private: private:
QMap<MAV_AUTOPILOT, QMap<QString, QmlObjectListModel*> > _categoryToMavCmdInfoListMap; QMap<MAV_AUTOPILOT, QMap<QString, QList<MAV_CMD> > > _categoryToMavCmdListMap;
QMap<MAV_CMD, MavCmdInfo*> _mavCmdInfoMap;
MissionCommandList _commonMissionCommands; ///< Mission command definitions for common generic mavlink use case
static const QString _categoryJsonKey; QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToCommonMissionCommands; ///< MAV_AUTOPILOT specific common overrides
static const QString _decimalPlacesJsonKey; QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToFixedWingMissionCommands; ///< MAV_AUTOPILOT specific fixed wing overrides
static const QString _defaultJsonKey; QMap<MAV_AUTOPILOT, MissionCommandList*> _autopilotToMultiRotorMissionCommands; ///< MAV_AUTOPILOT specific multi rotor overrides
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;