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 += \
src/Joystick/JoystickManager.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommands.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
......@@ -374,6 +375,7 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
......
......@@ -141,6 +141,12 @@
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
</qresource>
<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>
</RCC>
......@@ -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;
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:
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
protected:
/// 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:
/// List of supported mission commands. Empty list for all commands supported.
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
......@@ -127,3 +127,11 @@ QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
// Generic supports all commands
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
public:
// Overrides from FirmwarePlugin
virtual bool isCapable(FirmwareCapabilities capabilities) { Q_UNUSED(capabilities); return false; }
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
virtual QStringList flightModes(void) { return QStringList(); }
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
bool isCapable(FirmwareCapabilities capabilities) final { Q_UNUSED(capabilities); return false; }
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QStringList flightModes(void) final { return QStringList(); }
QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
int manualControlReservedButtonCount(void) final;
void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
void initializeVehicle(Vehicle* vehicle) final;
bool sendHomePositionToVehicle(void) final;
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam(void) const final { return QString(); }
QList<MAV_CMD> supportedMissionCommands(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
};
#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)
<< MAV_CMD_DO_CHANGE_SPEED;
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
public:
// Overrides from FirmwarePlugin
virtual bool isCapable(FirmwareCapabilities capabilities);
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
virtual QStringList flightModes(void);
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
bool isCapable(FirmwareCapabilities capabilities) final;
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QStringList flightModes(void) final;
QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
int manualControlReservedButtonCount(void) final;
void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
void initializeVehicle(Vehicle* vehicle) final;
bool sendHomePositionToVehicle(void) final;
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam(void) const final { return QString("SYS_AUTOSTART"); }
QList<MAV_CMD> supportedMissionCommands(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
private:
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 @@
#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 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;
};
#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
......@@ -134,45 +47,29 @@ public:
Q_INVOKABLE QString categoryFromCommand (MavlinkQmlSingleton::Qml_MAV_CMD command) 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
virtual void setToolbox(QGCToolbox* toolbox);
signals:
private:
void _loadMavCmdInfoJson(void);
void _createFirmwareSpecificLists(void);
void _setupMetaData(void);
bool _validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types);
void _createCategories(void);
MAV_AUTOPILOT _firmwareTypeFromVehicle(Vehicle* vehicle) const;
private:
QMap<MAV_AUTOPILOT, QMap<QString, QmlObjectListModel*> > _categoryToMavCmdInfoListMap;
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;
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
......@@ -161,7 +161,7 @@ void MissionController::sendMissionItems(void)
int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
{
MissionItem * newItem = new MissionItem(this);
MissionItem * newItem = new MissionItem(_activeVehicle, this);
newItem->setSequenceNumber(_missionItems->count());
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
......@@ -258,7 +258,7 @@ void MissionController::loadMissionFromFile(void)
if (versionOk) {
while (!in.atEnd()) {
MissionItem* item = new MissionItem();
MissionItem* item = new MissionItem(_activeVehicle, this);
if (item->load(in)) {
_missionItems->append(item);
......@@ -494,7 +494,7 @@ void MissionController::_initAllMissionItems(void)
homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
} else {
// Add the home position item to the front
homeItem = new MissionItem(this);
homeItem = new MissionItem(_activeVehicle, this);
homeItem->setSequenceNumber(0);
_missionItems->insert(0, homeItem);
}
......
......@@ -74,8 +74,9 @@ QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
return dbg;
}
MissionItem::MissionItem(QObject* parent)
MissionItem::MissionItem(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _rawEdit(false)
, _dirty(false)
, _sequenceNumber(0)
......@@ -107,7 +108,7 @@ MissionItem::MissionItem(QObject* parent)
, _param7MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
......@@ -121,7 +122,8 @@ MissionItem::MissionItem(QObject* parent)
setDefaultsForCommand();
}
MissionItem::MissionItem(int sequenceNumber,
MissionItem::MissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
......@@ -135,6 +137,7 @@ MissionItem::MissionItem(int sequenceNumber,
bool isCurrentItem,
QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _rawEdit(false)
, _dirty(false)
, _sequenceNumber(sequenceNumber)
......@@ -165,7 +168,7 @@ MissionItem::MissionItem(int sequenceNumber,
, _param7MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
......@@ -192,6 +195,7 @@ MissionItem::MissionItem(int sequenceNumber,
MissionItem::MissionItem(const MissionItem& other, QObject* parent)
: QObject(parent)
, _vehicle(NULL)
, _rawEdit(false)
, _dirty(false)
, _sequenceNumber(0)
......@@ -219,7 +223,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
, _param4MetaData(FactMetaData::valueTypeDouble)
, _syncingAltitudeRelativeToHomeAndFrame (false)
, _syncingHeadingDegreesAndParam4 (false)
, _mavCmdInfoMap(qgcApp()->toolbox()->missionCommands()->commandInfoMap())
, _missionCommands(qgcApp()->toolbox()->missionCommands())
{
// Need a good command and frame before we start passing signals around
_commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
......@@ -234,6 +238,8 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
const MissionItem& MissionItem::operator=(const MissionItem& other)
{
_vehicle = other._vehicle;
setCommand(other.command());
setFrame(other.frame());
setRawEdit(other._rawEdit);
......@@ -314,7 +320,8 @@ void MissionItem::_setupMetaData(void)
enumStrings.clear();
enumValues.clear();
foreach (const MavCmdInfo* mavCmdInfo, _mavCmdInfoMap) {
foreach (const MAV_CMD command, _missionCommands->commandsIds()) {
const MavCmdInfo* mavCmdInfo = _missionCommands->getMavCmdInfo(command, _vehicle);
enumStrings.append(mavCmdInfo->rawName());
enumValues.append(QVariant(mavCmdInfo->command()));
}
......@@ -488,8 +495,8 @@ void MissionItem::setParam7(double param)
bool MissionItem::standaloneCoordinate(void) const
{
if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->standaloneCoordinate();
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->standaloneCoordinate();
} else {
return false;
}
......@@ -497,8 +504,8 @@ bool MissionItem::standaloneCoordinate(void) const
bool MissionItem::specifiesCoordinate(void) const
{
if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->specifiesCoordinate();
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->specifiesCoordinate();
} else {
return false;
}
......@@ -506,8 +513,8 @@ bool MissionItem::specifiesCoordinate(void) const
QString MissionItem::commandDescription(void) const
{
if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
return _mavCmdInfoMap[(MAV_CMD)command()]->description();
if (_missionCommands->contains((MAV_CMD)command())) {
return _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->description();
} else {
qWarning() << "Should not ask for command description on unknown command";
return QString();
......@@ -561,7 +568,7 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
for (int i=1; i<=7; i++) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _mavCmdInfoMap[command]->paramInfoMap();
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap();
if (paramInfoMap.contains(i) && paramInfoMap[i]->enumStrings().count() == 0) {
Fact* paramFact = rgParamFacts[i-1];
......@@ -615,7 +622,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
MAV_CMD command = (MAV_CMD)this->command();
for (int i=1; i<=7; i++) {
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _mavCmdInfoMap[command]->paramInfoMap();
const QMap<int, MavCmdParamInfo*>& paramInfoMap = _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap();
if (paramInfoMap.contains(i) && paramInfoMap[i]->enumStrings().count() != 0) {
Fact* paramFact = rgParamFacts[i-1];
......@@ -649,7 +656,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool MissionItem::friendlyEditAllowed(void) const
{
if (_mavCmdInfoMap.contains((MAV_CMD)command()) && _mavCmdInfoMap[(MAV_CMD)command()]->friendlyEdit()) {
if (_missionCommands->contains((MAV_CMD)command()) && _missionCommands->getMavCmdInfo((MAV_CMD)command(), _vehicle)->friendlyEdit()) {
if (!autoContinue()) {
return false;
}
......@@ -752,8 +759,9 @@ void MissionItem::setDefaultsForCommand(void)
// We set these global defaults first, then if there are param defaults they will get reset
setParam7(defaultAltitude);
if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
foreach (const MavCmdParamInfo* paramInfo, _mavCmdInfoMap[(MAV_CMD)command()]->paramInfoMap()) {
MAV_CMD command = (MAV_CMD)this->command();
if (_missionCommands->contains(command)) {
foreach (const MavCmdParamInfo* paramInfo, _missionCommands->getMavCmdInfo(command, _vehicle)->paramInfoMap()) {
Fact* rgParamFacts[7] = { &_param1Fact, &_param2Fact, &_param3Fact, &_param4Fact, &_param5Fact, &_param6Fact, &_param7Fact };
rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
......@@ -782,11 +790,12 @@ void MissionItem::_sendCommandChanged(void)
QString MissionItem::commandName(void) const
{
if (_mavCmdInfoMap.contains((MAV_CMD)command())) {
const MavCmdInfo* mavCmdInfo = _mavCmdInfoMap[(MAV_CMD)command()];
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();
} else {
return QString("Unknown: %1").arg(command());
return QString("Unknown: %1").arg(command);
}
}
......
......@@ -46,9 +46,10 @@ class MissionItem : public QObject
Q_OBJECT
public:
MissionItem(QObject* parent = NULL);
MissionItem(Vehicle* vehicle, QObject* parent = NULL);
MissionItem(int sequenceNumber,
MissionItem(Vehicle* vehicle,
int sequenceNumber,
MAV_CMD command,
MAV_FRAME frame,
double param1,
......@@ -212,6 +213,7 @@ private:
void _setupMetaData(void);
private:
Vehicle* _vehicle; ///< Vehicle associated with this item, NULL for offline mode
bool _rawEdit;
bool _dirty;
int _sequenceNumber;
......@@ -257,7 +259,7 @@ private:
bool _syncingAltitudeRelativeToHomeAndFrame; ///< true: already in a sync signal, prevents signal loop
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
const QMap<MAV_CMD, MavCmdInfo*>& _mavCmdInfoMap;
const MissionCommands* _missionCommands;
};
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
......
......@@ -103,7 +103,8 @@ void MissionItemTest::_test(void)
qDebug() << "Command:" << info->command;
MissionItem* item = new MissionItem(1,
MissionItem* item = new MissionItem(NULL, // Vehicle
1,
info->command,
info->frame,
10.1234567,
......@@ -158,7 +159,7 @@ void MissionItemTest::_test(void)
QCOMPARE(factCount, expected->cFactValues);
// Validate that loading is working correctly
MissionItem* loadedItem = new MissionItem();
MissionItem* loadedItem = new MissionItem(NULL /* Vehicle */);
QTextStream loadStream(&savedItemString, QIODevice::ReadOnly);
QVERIFY(loadedItem->load(loadStream));
QCOMPARE(loadedItem->coordinate().latitude(), item->coordinate().latitude());
......@@ -180,7 +181,7 @@ void MissionItemTest::_test(void)
void MissionItemTest::_testDefaultValues(void)
{
MissionItem item;
MissionItem item(NULL /* Vehicle */);
item.setCommand(MAV_CMD_NAV_WAYPOINT);
item.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
......@@ -251,7 +251,8 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
_requestItemRetryCount = 0;
_itemIndicesToRead.removeOne(missionItem.seq);
MissionItem* item = new MissionItem(missionItem.seq,
MissionItem* item = new MissionItem(_vehicle,
missionItem.seq,
(MAV_CMD)missionItem.command,
(MAV_FRAME)missionItem.frame,
missionItem.param1,
......
......@@ -50,7 +50,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QmlObjectListModel* list = new QmlObjectListModel();
// Editor has a home position item on the front, so we do the same
MissionItem* homeItem = new MissionItem(this);
MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this);
homeItem->setHomePositionSpecialCase(true);
homeItem->setHomePositionValid(false);
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
......@@ -61,7 +61,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
for (size_t i=0; i<_cTestCases; i++) {
const TestCase_t* testCase = &_rgTestCases[i];
MissionItem* item = new MissionItem(list);
MissionItem* item = new MissionItem(NULL /* Vehicle */, list);
QTextStream loadStream(testCase->itemStream, QIODevice::ReadOnly);
QVERIFY(item->load(loadStream));
......
......@@ -29,6 +29,8 @@
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGCLoggingCategoryRegister* _instance = NULL;
......
......@@ -33,6 +33,7 @@
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
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