Commit 62acc335 authored by Don Gagne's avatar Don Gagne

Add mission item categories

- New mission command editor dialog
- New MissionCommands toolbox object to get command info
- Added APM mission item set
parent 41a81a78
......@@ -247,6 +247,7 @@ HEADERS += \
src/Joystick/JoystickManager.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/MissionCommands.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
......@@ -363,6 +364,7 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
......
......@@ -38,6 +38,7 @@
<file alias="QGroundControl/Controls/MainToolBarIndicators.qml">src/ui/toolbar/MainToolBarIndicators.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/QmlControls/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionCommandDialog.qml">src/QmlControls/MissionCommandDialog.qml</file>
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
......
......@@ -403,6 +403,7 @@ QGCView {
width: parent.width
readOnly: object.sequenceNumber == 0
visible: !readOnly || object.homePositionValid
qgcView: _root
onClicked: setCurrentItem(object.sequenceNumber)
......
......@@ -19,6 +19,7 @@
"description": "Travel to a position in 3D space.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "seconds",
......@@ -33,6 +34,7 @@
"description": "Travel to a position and Loiter around the specified radius indefinitely.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param3": {
"label": "Radius:",
"units": "meters",
......@@ -47,6 +49,7 @@
"description": "Travel to a position and Loiter around the specified radius for a number of turns.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Turns:",
"default": 1,
......@@ -66,6 +69,7 @@
"description": "Travel to a position and Loiter around the specified radius for an amount of time.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "seconds",
......@@ -84,7 +88,8 @@
"rawName": "MAV_CMD_NAV_RETURN_TO_LAUNCH",
"friendlyName": "Return Home",
"description": "Send the vehicle back to the home position.",
"friendlyEdit": true
"friendlyEdit": true,
"category": "Basic"
},
{
"id": 21,
......@@ -93,6 +98,7 @@
"description": "Land vehicle at the specified location.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Abort Alt:",
"units": "meters",
......@@ -113,6 +119,7 @@
"description": "Take off from the ground and travel towards the specified position.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Pitch:",
"units": "degreesConvert",
......@@ -138,6 +145,7 @@
"description": "Sets the region of interest for cameras.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Camera",
"param1": {
"label": "Mode:",
"enumStrings": "None,Next waypoint,Mission item,Location,ROI item",
......@@ -176,6 +184,7 @@
"friendlyName": "Delay",
"description": "Delay the mission for the number of seconds.",
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Hold:",
"units": "seconds",
......@@ -188,6 +197,7 @@
"rawName": "MAV_CMD_CONDITION_CHANGE_ALT",
"description": "Delay the mission until the specified altitide is reached.",
"friendlyName": "Wait for altitude",
"category": "Conditionals",
"param1": {
"label": "Rate:",
"units": "m/s",
......@@ -206,6 +216,7 @@
"rawName": "MAV_CMD_CONDITION_DISTANCE",
"description": "Delay the mission until within the specified distance of the next waypoint.",
"friendlyName": "Wait for distance",
"category": "Conditionals",
"param1": {
"label": "Distance:",
"units": "meters",
......@@ -218,6 +229,7 @@
"rawName": "MAV_CMD_CONDITION_YAW",
"friendlyName": "Wait for Heading",
"description": "Delay the mission until the specified heading is reached.",
"category": "Conditionals",
"param1": {
"label": "Heading:",
"units": "degrees",
......@@ -250,6 +262,7 @@
"friendlyName": "Jump to item",
"description": "Mission will continue at the specified item.",
"friendlyEdit": true,
"category": "Basic",
"param1": {
"label": "Item #:",
"default": 1,
......@@ -380,6 +393,7 @@
"description": "Sets the region of interest for cameras.",
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Camera",
"param1": {
"label": "Mode:",
"enumStrings": "None,Next waypoint,Mission item,Location,ROI item",
......@@ -403,6 +417,7 @@
"rawName": "MAV_CMD_DO_DIGICAM_CONFIGURE",
"friendlyName": "Camera config",
"description": "Configure onboard camera controller.",
"category": "Camera",
"param1": {
"label": "Mode:",
"default": 0,
......@@ -446,6 +461,7 @@
"friendlyName": "Camera control",
"rawName": "MAV_CMD_DO_DIGICAM_CONTROL",
"description": "Control onboard camera.",
"category": "Camera",
"param1": {
"label": "Session:",
"default": 0,
......@@ -483,6 +499,7 @@
"rawName": "MAV_CMD_DO_MOUNT_CONTROL",
"friendlyName": "Mount config",
"description": "Control antenna mount or camera.",
"category": "Camera",
"param1": {
"label": "Lat/Pitch:",
"default": 0,
......@@ -511,6 +528,7 @@
"rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST",
"friendlyName": "Camera trigger distance",
"description": "Set camera trigger distance.",
"category": "Camera",
"param1": {
"label": "Distance:",
"default": 25,
......
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 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/>.
======================================================================*/
#include "MissionCommands.h"
#include "FactMetaData.h"
#include <QStringList>
#include <QJsonDocument>
#include <QJsonParseError>
#include <QJsonArray>
#include <QDebug>
#include <QFile>
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
const QString MissionCommands::_categoryJsonKey (QStringLiteral("category"));
const QString MissionCommands::_decimalPlacesJsonKey (QStringLiteral("decimalPlaces"));
const QString MissionCommands::_defaultJsonKey (QStringLiteral("default"));
const QString MissionCommands::_descriptionJsonKey (QStringLiteral("description"));
const QString MissionCommands::_enumStringsJsonKey (QStringLiteral("enumStrings"));
const QString MissionCommands::_enumValuesJsonKey (QStringLiteral("enumValues"));
const QString MissionCommands::_friendlyEditJsonKey (QStringLiteral("friendlyEdit"));
const QString MissionCommands::_friendlyNameJsonKey (QStringLiteral("friendlyName"));
const QString MissionCommands::_idJsonKey (QStringLiteral("id"));
const QString MissionCommands::_labelJsonKey (QStringLiteral("label"));
const QString MissionCommands::_mavCmdInfoJsonKey (QStringLiteral("mavCmdInfo"));
const QString MissionCommands::_param1JsonKey (QStringLiteral("param1"));
const QString MissionCommands::_param2JsonKey (QStringLiteral("param2"));
const QString MissionCommands::_param3JsonKey (QStringLiteral("param3"));
const QString MissionCommands::_param4JsonKey (QStringLiteral("param4"));
const QString MissionCommands::_paramJsonKeyFormat (QStringLiteral("param%1"));
const QString MissionCommands::_rawNameJsonKey (QStringLiteral("rawName"));
const QString MissionCommands::_specifiesCoordinateJsonKey (QStringLiteral("specifiesCoordinate"));
const QString MissionCommands::_unitsJsonKey (QStringLiteral("units"));
const QString MissionCommands::_versionJsonKey (QStringLiteral("version"));
const QString MissionCommands::_degreesConvertUnits (QStringLiteral("degreesConvert"));
const QString MissionCommands::_degreesUnits (QStringLiteral("degrees"));
MissionCommands::MissionCommands(QGCApplication* app)
: QGCTool(app)
{
_loadMavCmdInfoJson();
}
bool MissionCommands::_validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types)
{
for (int i=0; i<keys.count(); i++) {
if (jsonObject.contains(keys[i])) {
if (jsonObject.value(keys[i]).type() != types[i]) {
qWarning() << "Incorrect type key:type:expected" << keys[i] << jsonObject.value(keys[i]).type() << types[i];
return false;
}
}
}
return true;
}
void MissionCommands::_loadMavCmdInfoJson(void)
{
QFile jsonFile(":/json/MavCmdInfo.json");
if (!jsonFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qWarning() << "Unable to open MavCmdInfo.json" << jsonFile.errorString();
return;
}
QByteArray bytes = jsonFile.readAll();
jsonFile.close();
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
qWarning() << "Unable to open json document" << jsonParseError.errorString();
return;
}
QJsonObject json = doc.object();
int version = json.value(_versionJsonKey).toInt();
if (version != 1) {
qWarning() << "Invalid version" << version;
return;
}
QJsonValue jsonValue = json.value(_mavCmdInfoJsonKey);
if (!jsonValue.isArray()) {
qWarning() << "mavCmdInfo not array";
return;
}
QJsonArray jsonArray = jsonValue.toArray();
foreach(QJsonValue info, jsonArray) {
if (!info.isObject()) {
qWarning() << "mavCmdArray should contain objects";
return;
}
QJsonObject jsonObject = info.toObject();
// Make sure we have the required keys
QStringList requiredKeys;
requiredKeys << _idJsonKey << _rawNameJsonKey;
foreach (QString key, requiredKeys) {
if (!jsonObject.contains(key)) {
qWarning() << "Mission required key" << key;
return;
}
}
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _specifiesCoordinateJsonKey << _friendlyEditJsonKey
<< _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _categoryJsonKey;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::String;
if (!_validateKeyTypes(jsonObject, keys, types)) {
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->_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->_specifiesCoordinate
<< mavCmdInfo->_friendlyEdit;
if (_mavCmdInfoMap.contains((MAV_CMD)mavCmdInfo->command())) {
qWarning() << "Duplicate command" << mavCmdInfo->command();
return;
}
_mavCmdInfoMap[mavCmdInfo->_command] = mavCmdInfo;
_commandList.append(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 (!_validateKeyTypes(paramObject, keys, types)) {
return;
}
mavCmdInfo->_friendlyEdit = true; // Assume friendly edit if we have params
if (!paramObject.contains(_labelJsonKey)) {
qWarning() << "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::defaultDecimalPlaces);
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 (QString enumValue, enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);
if (!convertOk) {
qWarning() << "Bad enumValue" << enumValue;
return;
}
paramInfo->_enumValues << QVariant(value);
}
if (paramInfo->_enumValues.count() != paramInfo->_enumStrings.count()) {
qWarning() << "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;
}
}
// We don't add categories till down here, since friendly edit isn't valid till here
if (mavCmdInfo->_command != MAV_CMD_NAV_LAST) {
// Don't add fake home postion command to categories
if (!_categories.contains(mavCmdInfo->category()) && mavCmdInfo->friendlyEdit()) {
// Only friendly edit commands go in category list
qCDebug(MissionCommandsLog) << "Adding new category";
_categories.append(mavCmdInfo->category());
_categoryToMavCmdInfoListMap[mavCmdInfo->category()] = new QmlObjectListModel(this);
}
if (mavCmdInfo->friendlyEdit()) {
// Only friendly edit commands go in category list
_categoryToMavCmdInfoListMap[mavCmdInfo->category()]->append(mavCmdInfo);
}
}
if (mavCmdInfo->friendlyEdit()) {
if (mavCmdInfo->description().isEmpty()) {
qWarning() << "Missing description" << mavCmdInfo->rawName();
return;
}
if (mavCmdInfo->rawName() == mavCmdInfo->friendlyName()) {
qWarning() << "Missing friendly name" << mavCmdInfo->rawName() << mavCmdInfo->friendlyName();
return;
}
}
}
}
/*=====================================================================
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 MissionCommands_H
#define MissionCommands_H
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MavlinkQmlSingleton.h"
#include <QObject>
#include <QString>
#include <QJsonObject>
#include <QJsonValue>
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
class MissionCommands;
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 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 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 _specifiesCoordinate;
friend class MissionCommands;
};
class MissionCommands : public QGCTool
{
Q_OBJECT
public:
MissionCommands(QGCApplication* app);
Q_PROPERTY(QStringList categories READ categories CONSTANT)
Q_PROPERTY(const QmlObjectListModel* commands READ commands CONSTANT)
Q_INVOKABLE QString categoryFromCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { return _mavCmdInfoMap[(MAV_CMD)command]->category(); }
Q_INVOKABLE const QVariant getCommandsForCategory(const QString& category) const { return QVariant::fromValue(_categoryToMavCmdInfoListMap[category]); }
const QStringList categories (void) const { return _categories; }
const QmlObjectListModel* commands (void) const { return &_commandList; }
const QMap<MAV_CMD, MavCmdInfo*>& commandInfoMap(void) const { return _mavCmdInfoMap; };
static const QString _degreesUnits;
static const QString _degreesConvertUnits;
signals:
private:
void _loadMavCmdInfoJson(void);
void _setupMetaData(void);
bool _validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types);
private:
QStringList _categories;
QMap<QString, QmlObjectListModel*> _categoryToMavCmdInfoListMap;
QmlObjectListModel _commandList;
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 _specifiesCoordinateJsonKey;
static const QString _unitsJsonKey;
static const QString _versionJsonKey;
};
#endif
......@@ -21,8 +21,6 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
#include <QStringList>
#include <QJsonDocument>
#include <QJsonParseError>
#include <QDebug>
#include "MissionItem.h"
......@@ -46,31 +44,6 @@ FactMetaData* MissionItem::_latitudeMetaData = NULL;
FactMetaData* MissionItem::_longitudeMetaData = NULL;
FactMetaData* MissionItem::_supportedCommandMetaData = NULL;
const QString MissionItem::_decimalPlacesJsonKey (QStringLiteral("decimalPlaces"));
const QString MissionItem::_defaultJsonKey (QStringLiteral("default"));
const QString MissionItem::_descriptionJsonKey (QStringLiteral("description"));
const QString MissionItem::_enumStringsJsonKey (QStringLiteral("enumStrings"));
const QString MissionItem::_enumValuesJsonKey (QStringLiteral("enumValues"));
const QString MissionItem::_friendlyEditJsonKey (QStringLiteral("friendlyEdit"));
const QString MissionItem::_friendlyNameJsonKey (QStringLiteral("friendlyName"));
const QString MissionItem::_idJsonKey (QStringLiteral("id"));
const QString MissionItem::_labelJsonKey (QStringLiteral("label"));
const QString MissionItem::_mavCmdInfoJsonKey (QStringLiteral("mavCmdInfo"));
const QString MissionItem::_param1JsonKey (QStringLiteral("param1"));
const QString MissionItem::_param2JsonKey (QStringLiteral("param2"));
const QString MissionItem::_param3JsonKey (QStringLiteral("param3"));
const QString MissionItem::_param4JsonKey (QStringLiteral("param4"));
const QString MissionItem::_paramJsonKeyFormat (QStringLiteral("param%1"));
const QString MissionItem::_rawNameJsonKey (QStringLiteral("rawName"));
const QString MissionItem::_specifiesCoordinateJsonKey (QStringLiteral("specifiesCoordinate"));
const QString MissionItem::_unitsJsonKey (QStringLiteral("units"));
const QString MissionItem::_versionJsonKey (QStringLiteral("version"));
const QString MissionItem::_degreesConvertUnits (QStringLiteral("degreesConvert"));
const QString MissionItem::_degreesUnits (QStringLiteral("degrees"));
QMap<MAV_CMD, MissionItem::MavCmdInfo_t> MissionItem::_mavCmdInfoMap;
struct EnumInfo_s {
const char * label;
MAV_FRAME frame;
......@@ -139,7 +112,12 @@ MissionItem::MissionItem(QObject* parent)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _syncingSupportedCommandAndCommand (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
_frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
_setupMetaData();
_connectSignals();
......@@ -169,8 +147,8 @@ MissionItem::MissionItem(int sequenceNumber,
, _homePositionSpecialCase(false)
, _homePositionValid(false)
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _commandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _frameFact (0, "Frame:", FactMetaData::valueTypeUint32)
, _commandFact (0, "", FactMetaData::valueTypeUint32)
, _frameFact (0, "", FactMetaData::valueTypeUint32)
, _param1Fact (0, "Param1:", FactMetaData::valueTypeDouble)
, _param2Fact (0, "Param2:", FactMetaData::valueTypeDouble)
, _param3Fact (0, "Param3:", FactMetaData::valueTypeDouble)
......@@ -189,7 +167,12 @@ MissionItem::MissionItem(int sequenceNumber,
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _syncingSupportedCommandAndCommand (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
_frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
_setupMetaData();
_connectSignals();
......@@ -220,8 +203,8 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
, _homePositionSpecialCase(false)
, _homePositionValid(false)
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
, _commandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _frameFact (0, "Frame:", FactMetaData::valueTypeUint32)
, _commandFact (0, "", FactMetaData::valueTypeUint32)
, _frameFact (0, "", FactMetaData::valueTypeUint32)
, _param1Fact (0, "Param1:", FactMetaData::valueTypeDouble)
, _param2Fact (0, "Param2:", FactMetaData::valueTypeDouble)
, _param3Fact (0, "Param3:", FactMetaData::valueTypeDouble)
......@@ -237,7 +220,12 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _syncingSupportedCommandAndCommand (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
_frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
_setupMetaData();
_connectSignals();
......@@ -315,180 +303,21 @@ void MissionItem::_connectSignals(void)
}
bool MissionItem::_validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types)
{
for (int i=0; i<keys.count(); i++) {
if (jsonObject.contains(keys[i])) {
if (jsonObject.value(keys[i]).type() != types[i]) {
qWarning() << "Incorrect type key:type:expected" << keys[i] << jsonObject.value(keys[i]).type() << types[i];
return false;
}
}
}
return true;
}
bool MissionItem::_loadMavCmdInfoJson(void)
{
QFile jsonFile(":/json/MavCmdInfo.json");
if (!jsonFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qWarning() << "Unable to open MavCmdInfo.json" << jsonFile.errorString();
return false;
}
QByteArray bytes = jsonFile.readAll();
jsonFile.close();
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
qWarning() << "Unable to open json document" << jsonParseError.errorString();
return false;
}
QJsonObject json = doc.object();
int version = json.value(_versionJsonKey).toInt();
if (version != 1) {
qWarning() << "Invalid version" << version;
return false;
}
QJsonValue jsonValue = json.value(_mavCmdInfoJsonKey);
if (!jsonValue.isArray()) {
qWarning() << "mavCmdInfo not array";
return false;
}
QJsonArray jsonArray = jsonValue.toArray();
foreach(QJsonValue info, jsonArray) {
if (!info.isObject()) {
qWarning() << "mavCmdArray should contain objects";
return false;
}
QJsonObject jsonObject = info.toObject();
// Make sure we have the required keys
QStringList requiredKeys;
requiredKeys << _idJsonKey << _rawNameJsonKey;
foreach (QString key, requiredKeys) {
if (!jsonObject.contains(key)) {
qWarning() << "Mission required key" << key;
return false;
}
}
// Validate key types
QStringList keys;
QList<QJsonValue::Type> types;
keys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _specifiesCoordinateJsonKey << _friendlyEditJsonKey
<< _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object;
if (!_validateKeyTypes(jsonObject, keys, types)) {
return false;
}
MavCmdInfo_t mavCmdInfo;
mavCmdInfo.command = (MAV_CMD) jsonObject.value(_idJsonKey).toInt();
mavCmdInfo.rawName = jsonObject.value(_rawNameJsonKey).toString();
mavCmdInfo.friendlyName = jsonObject.value(_friendlyNameJsonKey).toString(QString());
mavCmdInfo.description = jsonObject.value(_descriptionJsonKey).toString(QString());
mavCmdInfo.specifiesCoordinate = jsonObject.value(_specifiesCoordinateJsonKey).toBool(false);
mavCmdInfo.friendlyEdit = jsonObject.value(_friendlyEditJsonKey).toBool(false);
if (_mavCmdInfoMap.contains(mavCmdInfo.command)) {
qWarning() << "Duplicate command" << mavCmdInfo.command;
return false;
}
_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 (!_validateKeyTypes(paramObject, keys, types)) {
return false;
}
if (paramObject.contains(_labelJsonKey)) {
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].label = paramObject.value(_labelJsonKey).toString();
} else {
qWarning() << "param object missing label key" << mavCmdInfo.rawName << paramKey;
return false;
}
_mavCmdInfoMap[mavCmdInfo.command].friendlyEdit = true; // Assume friendly edit if we have params
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].defaultValue = paramObject.value(_defaultJsonKey).toDouble(0.0);
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].decimalPlaces = paramObject.value(_decimalPlacesJsonKey).toInt(FactMetaData::defaultDecimalPlaces);
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumStrings = paramObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].param = i;
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].units = paramObject.value(_unitsJsonKey).toString();
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
foreach (QString enumValue, enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);
if (!convertOk) {
qWarning() << "Bad enumValue" << enumValue;
return false;
}
_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumValues << QVariant(value);
}
if (_mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumStrings.count() != _mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumStrings.count()) {
qWarning() << "enum strings/values count mismatch" << _mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumStrings.count() << _mavCmdInfoMap[mavCmdInfo.command].paramInfoMap[i].enumStrings.count();
return false;
}
}
}
if (mavCmdInfo.friendlyEdit) {
if (mavCmdInfo.description.isEmpty()) {
qWarning() << "Missing description" << mavCmdInfo.rawName;
return false;
}
if (mavCmdInfo.rawName == mavCmdInfo.friendlyName) {
qWarning() << "Missing friendly name" << mavCmdInfo.rawName << mavCmdInfo.friendlyName;
return false;
}
}
}
return true;
}
void MissionItem::_setupMetaData(void)
{
QStringList enumStrings;
QVariantList enumValues;
if (!_altitudeMetaData) {
_loadMavCmdInfoJson();
_altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
_altitudeMetaData->setUnits("meters");
_altitudeMetaData->setDecimalPlaces(3);
enumStrings.clear();
enumValues.clear();
foreach (MavCmdInfo_t mavCmdInfo, _mavCmdInfoMap) {
enumStrings.append(mavCmdInfo.rawName);
enumValues.append(QVariant(mavCmdInfo.command));
foreach (const MavCmdInfo* mavCmdInfo, _mavCmdInfoMap) {
enumStrings.append(mavCmdInfo->rawName());
enumValues.append(QVariant(mavCmdInfo->command()));
}
_commandMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
_commandMetaData->setEnumInfo(enumStrings, enumValues);
......@@ -517,17 +346,17 @@ void MissionItem::_setupMetaData(void)
enumStrings.clear();
enumValues.clear();
// FIXME: Hack hardcode tp PX4
// FIXME: Hack hardcode to PX4
QList<MAV_CMD> supportedCommands = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR)->supportedMissionCommands();
if (supportedCommands.count()) {
foreach (MAV_CMD command, supportedCommands) {
enumStrings.append(_mavCmdInfoMap[command].friendlyName);
enumStrings.append(_mavCmdInfoMap[command]->friendlyName());
enumValues.append(QVariant(command));
}
} else {
foreach (MavCmdInfo_t mavCmdInfo, _mavCmdInfoMap) {
enumStrings.append(mavCmdInfo.friendlyName);
enumValues.append(QVariant(mavCmdInfo.command));
foreach (const MavCmdInfo* mavCmdInfo, _mavCmdInfoMap) {
enumStrings.append(mavCmdInfo->friendlyName());
enumValues.append(QVariant(mavCmdInfo->command()));
}
}
_supportedCommandMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
......@@ -678,12 +507,12 @@ void MissionItem::setParam7(double param)
bool MissionItem::specifiesCoordinate(void) const
{
return _mavCmdInfoMap[(MAV_CMD)command()].specifiesCoordinate;
return _mavCmdInfoMap[(MAV_CMD)command()]->specifiesCoordinate();
}
QString MissionItem::commandDescription(void) const
{
return _mavCmdInfoMap[(MAV_CMD)command()].description;
return _mavCmdInfoMap[(MAV_CMD)command()]->description();
}
void MissionItem::_clearParamMetaData(void)
......@@ -737,18 +566,21 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
for (int i=1; i<=7; i++) {
if (_mavCmdInfoMap[command].paramInfoMap.contains(i) && _mavCmdInfoMap[command].paramInfoMap[i].enumStrings.count() == 0) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];
paramFact->_setName(_mavCmdInfoMap[command].paramInfoMap[i].label);
paramMetaData->setDecimalPlaces(_mavCmdInfoMap[command].paramInfoMap[i].decimalPlaces);
paramMetaData->setEnumInfo(_mavCmdInfoMap[command].paramInfoMap[i].enumStrings, _mavCmdInfoMap[command].paramInfoMap[i].enumValues);
if (_mavCmdInfoMap[command].paramInfoMap[i].units == _degreesConvertUnits) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _mavCmdInfoMap[command]->paramInfoMap();
if (paramInfoMap.contains(i) && paramInfoMap[i]->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());
paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
if (paramInfo->units() == MissionCommands::_degreesConvertUnits) {
paramMetaData->setTranslators(_radiansToDegrees, _degreesToRadians);
paramMetaData->setUnits(_degreesUnits);
paramMetaData->setUnits(MissionCommands::_degreesUnits);
} else {
paramMetaData->setUnits(_mavCmdInfoMap[command].paramInfoMap[i].units);
paramMetaData->setUnits(paramInfo->units());
}
paramFact->setMetaData(paramMetaData);
model->append(paramFact);
......@@ -793,18 +625,21 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
MAV_CMD command = (MAV_CMD)this->command();
for (int i=1; i<=7; i++) {
if (_mavCmdInfoMap[command].paramInfoMap.contains(i) && _mavCmdInfoMap[command].paramInfoMap[i].enumStrings.count()) {
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];
paramFact->_setName(_mavCmdInfoMap[command].paramInfoMap[i].label);
paramMetaData->setDecimalPlaces(_mavCmdInfoMap[command].paramInfoMap[i].decimalPlaces);
paramMetaData->setEnumInfo(_mavCmdInfoMap[command].paramInfoMap[i].enumStrings, _mavCmdInfoMap[command].paramInfoMap[i].enumValues);
if (_mavCmdInfoMap[command].paramInfoMap[i].units == _degreesConvertUnits) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _mavCmdInfoMap[command]->paramInfoMap();
if (paramInfoMap.contains(i) && paramInfoMap[i]->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());
paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
if (paramInfo->units() == MissionCommands::_degreesConvertUnits) {
paramMetaData->setTranslators(_radiansToDegrees, _degreesToRadians);
paramMetaData->setUnits(_degreesUnits);
paramMetaData->setUnits(MissionCommands::_degreesUnits);
} else {
paramMetaData->setUnits(_mavCmdInfoMap[command].paramInfoMap[i].units);
paramMetaData->setUnits(paramInfo->units());
}
paramFact->setMetaData(paramMetaData);
model->append(paramFact);
......@@ -829,7 +664,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool MissionItem::friendlyEditAllowed(void) const
{
if (_mavCmdInfoMap[(MAV_CMD)command()].friendlyEdit) {
if (_mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) {
if (!autoContinue()) {
return false;
}
......@@ -935,10 +770,10 @@ void MissionItem::_syncCommandToSupportedCommand(const QVariant& value)
void MissionItem::setDefaultsForCommand(void)
{
foreach (ParamInfo_t paramInfo, _mavCmdInfoMap[(MAV_CMD)command()].paramInfoMap) {
foreach (const MavCmdParamInfo* paramInfo, _mavCmdInfoMap[(MAV_CMD)command()]->paramInfoMap()) {
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact };
rgParamFacts[paramInfo.param-1]->setRawValue(paramInfo.defaultValue);
rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
}
setParam7(defaultAltitude);
......@@ -964,9 +799,9 @@ void MissionItem::_sendCommandChanged(void)
QString MissionItem::commandName(void) const
{
MavCmdInfo_t& mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()];
const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()];
return mavCmdInfo.friendlyName.isEmpty() ? mavCmdInfo.rawName : mavCmdInfo.friendlyName;
return mavCmdInfo->friendlyName().isEmpty() ? mavCmdInfo->rawName() : mavCmdInfo->friendlyName();
}
QVariant MissionItem::_degreesToRadians(const QVariant& degrees)
......@@ -983,3 +818,8 @@ void MissionItem::_sendFriendlyEditAllowedChanged(void)
{
emit friendlyEditAllowedChanged(friendlyEditAllowed());
}
QString MissionItem::category(void) const
{
return qgcApp()->toolbox()->missionCommands()->categoryFromCommand(command());
}
......@@ -29,8 +29,6 @@
#include <QtQml>
#include <QTextStream>
#include <QGeoCoordinate>
#include <QJsonObject>
#include <QJsonValue>
#include "QGCMAVLink.h"
#include "QGC.h"
......@@ -39,6 +37,7 @@
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
......@@ -70,6 +69,7 @@ public:
const MissionItem& operator=(const MissionItem& other);
Q_PROPERTY(double azimuth READ azimuth WRITE setAzimuth NOTIFY azimuthChanged) ///< Azimuth to previous waypoint
Q_PROPERTY(QString category READ category NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandChanged)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged)
......@@ -97,6 +97,7 @@ public:
// Property accesors
double azimuth (void) const { return _azimuth; }
QString category (void) const;
MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_commandFact.cookedValue().toInt(); };
QString commandDescription (void) const;
QString commandName (void) const;
......@@ -206,34 +207,12 @@ private slots:
private:
void _clearParamMetaData(void);
void _connectSignals(void);
bool _loadMavCmdInfoJson(void);
void _setupMetaData(void);
bool _validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types);
static QVariant _degreesToRadians(const QVariant& degrees);
static QVariant _radiansToDegrees(const QVariant& radians);
private:
typedef struct {
double defaultValue;
int decimalPlaces;
QStringList enumStrings;
QVariantList enumValues;
QString label;
int param;
QString units;
} ParamInfo_t;
typedef struct {
MAV_CMD command;
QString description;
bool friendlyEdit;
QString friendlyName;
QMap<int, ParamInfo_t> paramInfoMap;
QString rawName;
bool specifiesCoordinate;
} MavCmdInfo_t;
bool _rawEdit;
bool _dirty;
int _sequenceNumber;
......@@ -279,30 +258,7 @@ private:
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
bool _syncingSupportedCommandAndCommand; ///< true: already in a sync signal, prevents signal loop
static QMap<MAV_CMD, MavCmdInfo_t> _mavCmdInfoMap;
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 _specifiesCoordinateJsonKey;
static const QString _unitsJsonKey;
static const QString _versionJsonKey;
static const QString _degreesUnits;
static const QString _degreesConvertUnits;
const QMap<MAV_CMD, MavCmdInfo*>& _mavCmdInfoMap;
};
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
......
......@@ -88,6 +88,7 @@
#include "CoordinateVector.h"
#include "MainToolBarController.h"
#include "MissionController.h"
#include "MissionCommands.h"
#include "FlightDisplayViewController.h"
#include "VideoSurface.h"
#include "VideoReceiver.h"
......@@ -338,6 +339,13 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<QGCPalette> ("QGroundControl.Palette", 1, 0, "QGCPalette");
qmlRegisterType<QGCMapPalette> ("QGroundControl.Palette", 1, 0, "QGCMapPalette");
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<MissionCommands> ("QGroundControl", 1, 0, "MissionCommands", "Reference only");
qmlRegisterUncreatableType<QGCQGeoCoordinate> ("QGroundControl", 1, 0, "QGCQGeoCoordinate", "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<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Reference only");
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Reference only");
qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only");
......@@ -345,11 +353,6 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterUncreatableType<QGCQGeoCoordinate> ("QGroundControl", 1, 0, "QGCQGeoCoordinate", "Reference only");
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", "Reference only");
qmlRegisterUncreatableType<VideoSurface> ("QGroundControl", 1, 0, "VideoSurface", "Reference only");
qmlRegisterUncreatableType<VideoReceiver> ("QGroundControl", 1, 0, "VideoReceiver", "Reference only");
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
qmlRegisterType<FlightModesComponentController> ("QGroundControl.Controllers", 1, 0, "FlightModesComponentController");
......
......@@ -21,73 +21,78 @@
======================================================================*/
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "AutoPilotPluginManager.h"
#include "FactSystem.h"
#include "FirmwarePluginManager.h"
#include "FlightMapSettings.h"
#include "GAudioOutput.h"
#include "HomePositionManager.h"
#include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h"
#include "JoystickManager.h"
#include "GAudioOutput.h"
#include "AutoPilotPluginManager.h"
#include "UASMessageHandler.h"
#include "FactSystem.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MissionCommands.h"
#include "MultiVehicleManager.h"
#include "QGCImageProvider.h"
#include "UASMessageHandler.h"
QGCToolbox::QGCToolbox(QGCApplication* app)
: _firmwarePluginManager(NULL)
: _audioOutput(NULL)
, _autopilotPluginManager(NULL)
, _linkManager(NULL)
, _multiVehicleManager(NULL)
, _mavlinkProtocol(NULL)
, _factSystem(NULL)
, _firmwarePluginManager(NULL)
, _flightMapSettings(NULL)
, _homePositionManager(NULL)
, _imageProvider(NULL)
, _joystickManager(NULL)
, _audioOutput(NULL)
, _linkManager(NULL)
, _mavlinkProtocol(NULL)
, _missionCommands(NULL)
, _multiVehicleManager(NULL)
, _uasMessageHandler(NULL)
, _factSystem(NULL)
, _imageProvider(NULL)
{
_firmwarePluginManager = new FirmwarePluginManager(app);
_audioOutput = new GAudioOutput(app);
_autopilotPluginManager = new AutoPilotPluginManager(app);
_factSystem = new FactSystem(app);
_firmwarePluginManager = new FirmwarePluginManager(app);
_flightMapSettings = new FlightMapSettings(app);
_homePositionManager = new HomePositionManager(app);
_factSystem = new FactSystem(app);
_imageProvider = new QGCImageProvider(app);
_joystickManager = new JoystickManager(app);
_linkManager = new LinkManager(app);
_multiVehicleManager = new MultiVehicleManager(app);
_mavlinkProtocol = new MAVLinkProtocol(app);
_joystickManager = new JoystickManager(app);
_audioOutput = new GAudioOutput(app);
_missionCommands = new MissionCommands(app);
_multiVehicleManager = new MultiVehicleManager(app);
_uasMessageHandler = new UASMessageHandler(app);
_imageProvider = new QGCImageProvider(app);
_firmwarePluginManager->setToolbox(this);
_audioOutput->setToolbox(this);
_autopilotPluginManager->setToolbox(this);
_factSystem->setToolbox(this);
_firmwarePluginManager->setToolbox(this);
_flightMapSettings->setToolbox(this);
_homePositionManager->setToolbox(this);
_factSystem->setToolbox(this);
_imageProvider->setToolbox(this);
_joystickManager->setToolbox(this);
_linkManager->setToolbox(this);
_multiVehicleManager->setToolbox(this);
_mavlinkProtocol->setToolbox(this);
_joystickManager->setToolbox(this);
_audioOutput->setToolbox(this);
_missionCommands->setToolbox(this);
_multiVehicleManager->setToolbox(this);
_uasMessageHandler->setToolbox(this);
_imageProvider->setToolbox(this);
}
QGCToolbox::~QGCToolbox()
{
delete _firmwarePluginManager;
delete _audioOutput;
delete _autopilotPluginManager;
delete _linkManager;
delete _multiVehicleManager;
delete _mavlinkProtocol;
delete _factSystem;
delete _firmwarePluginManager;
delete _flightMapSettings;
delete _homePositionManager;
delete _joystickManager;
delete _audioOutput;
delete _linkManager;
delete _mavlinkProtocol;
delete _missionCommands;
delete _multiVehicleManager;
delete _uasMessageHandler;
delete _factSystem;
}
QGCTool::QGCTool(QGCApplication* app)
......
......@@ -26,19 +26,20 @@
#include <QObject>
class QGCApplication;
class AutoPilotPluginManager;
class FactSystem;
class FirmwarePluginManager;
class FlightMapSettings;
class GAudioOutput;
class HomePositionManager;
class JoystickManager;
class LinkManager;
class MAVLinkProtocol;
class MissionCommands;
class MultiVehicleManager;
class JoystickManager;
class UASMessageHandler;
class HomePositionManager;
class FlightMapSettings;
class GAudioOutput;
class FirmwarePluginManager;
class AutoPilotPluginManager;
class FactSystem;
class QGCApplication;
class QGCImageProvider;
class UASMessageHandler;
/// This is used to manage all of our top level services/tools
class QGCToolbox {
......@@ -47,31 +48,33 @@ public:
QGCToolbox(QGCApplication* app);
~QGCToolbox();
AutoPilotPluginManager* autopilotPluginManager(void) { return _autopilotPluginManager; }
FirmwarePluginManager* firmwarePluginManager(void) { return _firmwarePluginManager; }
FlightMapSettings* flightMapSettings(void) { return _flightMapSettings; }
GAudioOutput* audioOutput(void) { return _audioOutput; }
HomePositionManager* homePositionManager(void) { return _homePositionManager; }
JoystickManager* joystickManager(void) { return _joystickManager; }
LinkManager* linkManager(void) { return _linkManager; }
MAVLinkProtocol* mavlinkProtocol(void) { return _mavlinkProtocol; }
MissionCommands* missionCommands(void) { return _missionCommands; }
MultiVehicleManager* multiVehicleManager(void) { return _multiVehicleManager; }
JoystickManager* joystickManager(void) { return _joystickManager; }
UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; }
HomePositionManager* homePositionManager(void) { return _homePositionManager; }
FlightMapSettings* flightMapSettings(void) { return _flightMapSettings; }
GAudioOutput* audioOutput(void) { return _audioOutput; }
FirmwarePluginManager* firmwarePluginManager(void) { return _firmwarePluginManager; }
AutoPilotPluginManager* autopilotPluginManager(void) { return _autopilotPluginManager; }
QGCImageProvider* imageProvider() { return _imageProvider; }
UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; }
private:
FirmwarePluginManager* _firmwarePluginManager;
GAudioOutput* _audioOutput;
AutoPilotPluginManager* _autopilotPluginManager;
LinkManager* _linkManager;
MultiVehicleManager* _multiVehicleManager;
MAVLinkProtocol* _mavlinkProtocol;
FactSystem* _factSystem;
FirmwarePluginManager* _firmwarePluginManager;
FlightMapSettings* _flightMapSettings;
HomePositionManager* _homePositionManager;
QGCImageProvider* _imageProvider;
JoystickManager* _joystickManager;
GAudioOutput* _audioOutput;
LinkManager* _linkManager;
MAVLinkProtocol* _mavlinkProtocol;
MissionCommands* _missionCommands;
MultiVehicleManager* _multiVehicleManager;
UASMessageHandler* _uasMessageHandler;
FactSystem* _factSystem;
QGCImageProvider* _imageProvider;
};
/// This is the base class for all tools
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 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/>.
======================================================================*/
import QtQuick 2.5
import QtQuick.Controls 1.4
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
QGCViewDialog {
property var missionItem
QGCPalette { id: qgcPal }
QGCLabel {
id: categoryLabel
anchors.baseline: categoryCombo.baseline
text: "Category:"
}
QGCComboBox {
id: categoryCombo
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: categoryLabel.right
anchors.right: parent.right
model: QGroundControl.missionCommands.categories
function categorySelected(category) {
commandList.model = QGroundControl.missionCommands.getCommandsForCategory(category)
console.log("changing model", category)
}
Component.onCompleted: {
var category = missionItem.category
currentIndex = find(category)
categorySelected(category)
}
onActivated: categorySelected(textAt(index))
}
ListView {
id: commandList
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.left: parent.left
anchors.right: parent.right
anchors.top: categoryCombo.bottom
anchors.bottom: parent.bottom
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical
onModelChanged: {
var currentCategory = categoryCombo.currentText
currentIndex = -1
if (missionItem.category == currentCategory) {
var commandList = QGroundControl.missionCommands.getCommandsForCategory(currentCategory)
for (var i=0; i<commandList.count; i++) {
if (commandList.get(i).command == missionItem.command) {
currentIndex = i
break
}
}
}
}
highlight: Rectangle {
color: qgcPal.buttonHighlight
}
delegate: Rectangle {
width: parent.width
height: commandColumn.height + ScreenTools.defaultFontPixelSize
color: currentItem ? qgcPal.buttonHighlight : qgcPal.button
property var mavCmdInfo: object
property bool currentItem: commandList.currentItem == this
property var textColor: currentItem ? qgcPal.buttonHighlightText : qgcPal.buttonText
Column {
id: commandColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
QGCLabel {
text: mavCmdInfo.friendlyName
color: textColor
}
QGCLabel {
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.right: parent.right
text: mavCmdInfo.description
wrapMode: Text.WordWrap
color: textColor
}
}
MouseArea {
anchors.fill: parent
onClicked: {
missionItem.command = mavCmdInfo.command
accept()
}
}
}
} // ListView
} // QGCViewDialog
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
......@@ -15,6 +16,7 @@ Rectangle {
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
property var qgcView ///< QGCView control used for showing dialogs
signal clicked
signal remove
......@@ -56,8 +58,8 @@ Rectangle {
Image {
id: rawEdit
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 8
anchors.left: label.right
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.right: parent.right
anchors.verticalCenter: commandPicker.verticalCenter
width: commandPicker.height
height: commandPicker.height
......@@ -70,16 +72,24 @@ Rectangle {
}
}
FactComboBox {
id: commandPicker
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: rawEdit.right
anchors.right: parent.right
indexModel: false
fact: missionItem.supportedCommand
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit
QGCButton {
id: commandPicker
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2
anchors.rightMargin: ScreenTools.defaultFontPixelWidth
anchors.left: label.right
anchors.right: rawEdit.left
visible: missionItem.sequenceNumber != 0 && missionItem.isCurrentItem && !missionItem.rawEdit
text: missionItem.commandName
Component {
id: commandDialog
MissionCommandDialog {
missionItem: _root.missionItem
}
}
onActivated: missionItem.commandByIndex = index
onClicked: qgcView.showDialog(commandDialog, "Select Mission Command", 40, StandardButton.Cancel)
}
Rectangle {
......
......@@ -306,7 +306,7 @@ FactPanel {
QGCButton {
id: __rejectButton
anchors.right: __acceptButton.left
anchors.right: __acceptButton.visible ? __acceptButton.left : parent.right
anchors.bottom: parent.bottom
onClicked: __dialogComponentLoader.item.reject()
......
......@@ -6,6 +6,7 @@ ExclusiveGroupItem 1.0 ExclusiveGroupItem.qml
IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml
MainToolBar 1.0 MainToolBar.qml
MissionCommandDialog 1.0 MissionCommandDialog.qml
MissionItemEditor 1.0 MissionItemEditor.qml
MissionItemIndexLabel 1.0 MissionItemIndexLabel.qml
ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml
......
......@@ -29,16 +29,17 @@
#include <QSettings>
static const char* kQmlGlobalKeyName = "QGCQml";
static const char* kQmlGlobalKeyName = "QGCQml";
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey = "VirtualTabletJoystick";
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent)
: QObject(parent)
, _multiVehicleManager(toolbox->multiVehicleManager())
, _linkManager(toolbox->linkManager())
, _homePositionManager(toolbox->homePositionManager())
, _flightMapSettings(toolbox->flightMapSettings())
, _homePositionManager(toolbox->homePositionManager())
, _linkManager(toolbox->linkManager())
, _missionCommands(toolbox->missionCommands())
, _multiVehicleManager(toolbox->multiVehicleManager())
, _virtualTabletJoystick(false)
{
QSettings settings;
......
......@@ -34,6 +34,7 @@
#include "LinkManager.h"
#include "HomePositionManager.h"
#include "FlightMapSettings.h"
#include "MissionCommands.h"
#ifdef QT_DEBUG
#include "MockLink.h"
......@@ -48,10 +49,11 @@ class QGroundControlQmlGlobal : public QObject
public:
QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent = NULL);
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(HomePositionManager* homePositionManager READ homePositionManager CONSTANT)
Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings 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
......@@ -85,10 +87,11 @@ public:
// Property accesors
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
HomePositionManager* homePositionManager () { return _homePositionManager; }
LinkManager* linkManager () { return _linkManager; }
MissionCommands* missionCommands () { return _missionCommands; }
MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
HomePositionManager* homePositionManager () { return _homePositionManager; }
FlightMapSettings* flightMapSettings () { return _flightMapSettings; }
qreal zOrderTopMost () { return 1000; }
qreal zOrderWidgets () { return 100; }
......@@ -133,10 +136,11 @@ private:
void _startMockLink(MockConfiguration* mockConfig);
#endif
MultiVehicleManager* _multiVehicleManager;
LinkManager* _linkManager;
HomePositionManager* _homePositionManager;
FlightMapSettings* _flightMapSettings;
HomePositionManager* _homePositionManager;
LinkManager* _linkManager;
MissionCommands* _missionCommands;
MultiVehicleManager* _multiVehicleManager;
bool _virtualTabletJoystick;
......
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