Commit 2debdad3 authored by DonLakeFlyer's avatar DonLakeFlyer

parent ddf99734
...@@ -752,23 +752,23 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void) ...@@ -752,23 +752,23 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
}; };
} }
QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const QString APMFirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
{ {
switch (vehicleType) { switch (vehicleClass) {
case MAV_TYPE_GENERIC: case QGCMAVLink::VehicleClassGeneric:
return QStringLiteral(":/json/APM-MavCmdInfoCommon.json"); return QStringLiteral(":/json/APM-MavCmdInfoCommon.json");
case MAV_TYPE_FIXED_WING: case QGCMAVLink::VehicleClassFixedWing:
return QStringLiteral(":/json/APM-MavCmdInfoFixedWing.json"); return QStringLiteral(":/json/APM-MavCmdInfoFixedWing.json");
case MAV_TYPE_QUADROTOR: case QGCMAVLink::VehicleClassMultiRotor:
return QStringLiteral(":/json/APM-MavCmdInfoMultiRotor.json"); return QStringLiteral(":/json/APM-MavCmdInfoMultiRotor.json");
case MAV_TYPE_VTOL_QUADROTOR: case QGCMAVLink::VehicleClassVTOL:
return QStringLiteral(":/json/APM-MavCmdInfoVTOL.json"); return QStringLiteral(":/json/APM-MavCmdInfoVTOL.json");
case MAV_TYPE_SUBMARINE: case QGCMAVLink::VehicleClassSub:
return QStringLiteral(":/json/APM-MavCmdInfoSub.json"); return QStringLiteral(":/json/APM-MavCmdInfoSub.json");
case MAV_TYPE_GROUND_ROVER: case QGCMAVLink::VehicleClassRoverBoat:
return QStringLiteral(":/json/APM-MavCmdInfoRover.json"); return QStringLiteral(":/json/APM-MavCmdInfoRover.json");
default: default:
qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
return QString(); return QString();
} }
} }
......
...@@ -97,7 +97,7 @@ public: ...@@ -97,7 +97,7 @@ public:
virtual void initializeStreamRates (Vehicle* vehicle); virtual void initializeStreamRates (Vehicle* vehicle);
void initializeVehicle (Vehicle* vehicle) override; void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override; bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString getVersionParam (void) override { return QStringLiteral("SYSID_SW_MREV"); } QString getVersionParam (void) override { return QStringLiteral("SYSID_SW_MREV"); }
QString _internalParameterMetaDataFile (Vehicle* vehicle) override; QString _internalParameterMetaDataFile (Vehicle* vehicle) override;
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override; FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
......
...@@ -24,11 +24,11 @@ APMFirmwarePluginFactory::APMFirmwarePluginFactory(void) ...@@ -24,11 +24,11 @@ APMFirmwarePluginFactory::APMFirmwarePluginFactory(void)
} }
QList<MAV_AUTOPILOT> APMFirmwarePluginFactory::supportedFirmwareTypes(void) const QList<QGCMAVLink::FirmwareClass_t> APMFirmwarePluginFactory::supportedFirmwareClasses(void) const
{ {
QList<MAV_AUTOPILOT> list; QList<QGCMAVLink::FirmwareClass_t> list;
list.append(MAV_AUTOPILOT_ARDUPILOTMEGA); list.append(QGCMAVLink::FirmwareClassArduPilot);
return list; return list;
} }
......
...@@ -7,8 +7,7 @@ ...@@ -7,8 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#ifndef APMFirmwarePluginFactory_H #pragma once
#define APMFirmwarePluginFactory_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
...@@ -24,8 +23,8 @@ class APMFirmwarePluginFactory : public FirmwarePluginFactory ...@@ -24,8 +23,8 @@ class APMFirmwarePluginFactory : public FirmwarePluginFactory
public: public:
APMFirmwarePluginFactory(void); APMFirmwarePluginFactory(void);
QList<MAV_AUTOPILOT> supportedFirmwareTypes (void) const final; QList<QGCMAVLink::FirmwareClass_t> supportedFirmwareClasses(void) const final;
FirmwarePlugin* firmwarePluginForAutopilot (MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) final; FirmwarePlugin* firmwarePluginForAutopilot (MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) final;
private: private:
ArduCopterFirmwarePlugin* _arduCopterPluginInstance; ArduCopterFirmwarePlugin* _arduCopterPluginInstance;
...@@ -33,5 +32,3 @@ private: ...@@ -33,5 +32,3 @@ private:
ArduRoverFirmwarePlugin* _arduRoverPluginInstance; ArduRoverFirmwarePlugin* _arduRoverPluginInstance;
ArduSubFirmwarePlugin* _arduSubPluginInstance; ArduSubFirmwarePlugin* _arduSubPluginInstance;
}; };
#endif
...@@ -34,11 +34,9 @@ FirmwarePluginFactory::FirmwarePluginFactory(void) ...@@ -34,11 +34,9 @@ FirmwarePluginFactory::FirmwarePluginFactory(void)
FirmwarePluginFactoryRegister::instance()->registerPluginFactory(this); FirmwarePluginFactoryRegister::instance()->registerPluginFactory(this);
} }
QList<MAV_TYPE> FirmwarePluginFactory::supportedVehicleTypes(void) const QList<QGCMAVLink::VehicleClass_t> FirmwarePluginFactory::supportedVehicleClasses(void) const
{ {
QList<MAV_TYPE> vehicleTypes; return QGCMAVLink::allVehicleClasses();
vehicleTypes << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE;
return vehicleTypes;
} }
FirmwarePluginFactoryRegister* FirmwarePluginFactoryRegister::instance(void) FirmwarePluginFactoryRegister* FirmwarePluginFactoryRegister::instance(void)
...@@ -182,23 +180,23 @@ QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void) ...@@ -182,23 +180,23 @@ QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
return QList<MAV_CMD>(); return QList<MAV_CMD>();
} }
QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const QString FirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
{ {
switch (vehicleType) { switch (vehicleClass) {
case MAV_TYPE_GENERIC: case QGCMAVLink::VehicleClassGeneric:
return QStringLiteral(":/json/MavCmdInfoCommon.json"); return QStringLiteral(":/json/MavCmdInfoCommon.json");
case MAV_TYPE_FIXED_WING: case QGCMAVLink::VehicleClassFixedWing:
return QStringLiteral(":/json/MavCmdInfoFixedWing.json"); return QStringLiteral(":/json/MavCmdInfoFixedWing.json");
case MAV_TYPE_QUADROTOR: case QGCMAVLink::VehicleClassMultiRotor:
return QStringLiteral(":/json/MavCmdInfoMultiRotor.json"); return QStringLiteral(":/json/MavCmdInfoMultiRotor.json");
case MAV_TYPE_VTOL_QUADROTOR: case QGCMAVLink::VehicleClassVTOL:
return QStringLiteral(":/json/MavCmdInfoVTOL.json"); return QStringLiteral(":/json/MavCmdInfoVTOL.json");
case MAV_TYPE_SUBMARINE: case QGCMAVLink::VehicleClassSub:
return QStringLiteral(":/json/MavCmdInfoSub.json"); return QStringLiteral(":/json/MavCmdInfoSub.json");
case MAV_TYPE_GROUND_ROVER: case QGCMAVLink::VehicleClassRoverBoat:
return QStringLiteral(":/json/MavCmdInfoRover.json"); return QStringLiteral(":/json/MavCmdInfoRover.json");
default: default:
qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
return QString(); return QString();
} }
} }
...@@ -787,22 +785,6 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc ...@@ -787,22 +785,6 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
return false; return false;
} }
bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const
{
switch (vehicle->vehicleType()) {
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
return true;
default:
return false;
}
}
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle) QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{ {
return new QGCCameraManager(vehicle); return new QGCCameraManager(vehicle);
......
...@@ -241,8 +241,8 @@ public: ...@@ -241,8 +241,8 @@ public:
virtual QList<MAV_CMD> supportedMissionCommands(void); virtual QList<MAV_CMD> supportedMissionCommands(void);
/// Returns the name of the mission command json override file for the specified vehicle type. /// Returns the name of the mission command json override file for the specified vehicle type.
/// @param vehicleType Vehicle type to return file for, MAV_TYPE_GENERIC is a request for overrides for all vehicle types /// @param vehicleClass Vehicle class to return file for, VehicleClassGeneric is a request for overrides for all vehicle types
virtual QString missionCommandOverrides(MAV_TYPE vehicleType) const; virtual QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const;
/// Returns the mapping structure which is used to map from one parameter name to another based on firmware version. /// Returns the mapping structure which is used to map from one parameter name to another based on firmware version.
virtual const remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const; virtual const remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const;
...@@ -316,9 +316,6 @@ public: ...@@ -316,9 +316,6 @@ public:
/// @return true: vehicle has gimbal, false: gimbal support unknown /// @return true: vehicle has gimbal, false: gimbal support unknown
virtual bool hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported); virtual bool hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported);
/// Returns true if the vehicle is a VTOL
virtual bool isVtol(const Vehicle* vehicle) const;
/// Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value. /// Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode); virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode);
...@@ -383,11 +380,11 @@ public: ...@@ -383,11 +380,11 @@ public:
/// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT. /// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT.
virtual FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) = 0; virtual FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) = 0;
/// @return List of firmware types this plugin supports. /// @return List of firmware classes this plugin supports.
virtual QList<MAV_AUTOPILOT> supportedFirmwareTypes(void) const = 0; virtual QList<QGCMAVLink::FirmwareClass_t> supportedFirmwareClasses(void) const = 0;
/// @return List of vehicle types this plugin supports. /// @return List of vehicle classes this plugin supports.
virtual QList<MAV_TYPE> supportedVehicleTypes(void) const; virtual QList<QGCMAVLink::VehicleClass_t> supportedVehicleClasses(void) const;
}; };
class FirmwarePluginFactoryRegister : public QObject class FirmwarePluginFactoryRegister : public QObject
......
...@@ -26,33 +26,35 @@ FirmwarePluginManager::~FirmwarePluginManager() ...@@ -26,33 +26,35 @@ FirmwarePluginManager::~FirmwarePluginManager()
delete _genericFirmwarePlugin; delete _genericFirmwarePlugin;
} }
QList<MAV_AUTOPILOT> FirmwarePluginManager::supportedFirmwareTypes(void) QList<QGCMAVLink::FirmwareClass_t> FirmwarePluginManager::supportedFirmwareClasses(void)
{ {
if (_supportedFirmwareTypes.isEmpty()) { if (_supportedFirmwareClasses.isEmpty()) {
QList<FirmwarePluginFactory*> factoryList = FirmwarePluginFactoryRegister::instance()->pluginFactories(); QList<FirmwarePluginFactory*> factoryList = FirmwarePluginFactoryRegister::instance()->pluginFactories();
for (int i = 0; i < factoryList.count(); i++) { for (int i = 0; i < factoryList.count(); i++) {
_supportedFirmwareTypes.append(factoryList[i]->supportedFirmwareTypes()); _supportedFirmwareClasses.append(factoryList[i]->supportedFirmwareClasses());
} }
_supportedFirmwareTypes.append(MAV_AUTOPILOT_GENERIC); _supportedFirmwareClasses.append(QGCMAVLink::FirmwareClassGeneric);
} }
return _supportedFirmwareTypes; return _supportedFirmwareClasses;
} }
QList<MAV_TYPE> FirmwarePluginManager::supportedVehicleTypes(MAV_AUTOPILOT firmwareType) QList<QGCMAVLink::VehicleClass_t> FirmwarePluginManager::supportedVehicleClasses(QGCMAVLink::FirmwareClass_t firmwareClass)
{ {
QList<MAV_TYPE> vehicleTypes; QList<QGCMAVLink::VehicleClass_t> vehicleClasses;
FirmwarePluginFactory* factory = _findPluginFactory(firmwareType); FirmwarePluginFactory* factory = _findPluginFactory(firmwareClass);
if (factory) { if (factory) {
vehicleTypes = factory->supportedVehicleTypes(); vehicleClasses = factory->supportedVehicleClasses();
} else if (firmwareType == MAV_AUTOPILOT_GENERIC) { } else if (firmwareClass == QGCMAVLink::FirmwareClassGeneric) {
vehicleTypes << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE; // Generic supports all specific vehicle class
vehicleClasses = QGCMAVLink::allVehicleClasses();
vehicleClasses.removeOne(QGCMAVLink::VehicleClassGeneric);
} else { } else {
qWarning() << "Request for unknown firmware plugin factory" << firmwareType; qWarning() << "Request for unknown firmware plugin factory" << firmwareClass;
} }
return vehicleTypes; return vehicleClasses;
} }
FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType) FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType)
...@@ -62,8 +64,6 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT ...@@ -62,8 +64,6 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT
if (factory) { if (factory) {
plugin = factory->firmwarePluginForAutopilot(firmwareType, vehicleType); plugin = factory->firmwarePluginForAutopilot(firmwareType, vehicleType);
} else if (firmwareType != MAV_AUTOPILOT_GENERIC) {
qWarning() << "Request for unknown firmware plugin factory" << firmwareType;
} }
if (!plugin) { if (!plugin) {
...@@ -77,14 +77,14 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT ...@@ -77,14 +77,14 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT
return plugin; return plugin;
} }
FirmwarePluginFactory* FirmwarePluginManager::_findPluginFactory(MAV_AUTOPILOT firmwareType) FirmwarePluginFactory* FirmwarePluginManager::_findPluginFactory(QGCMAVLink::FirmwareClass_t firmwareClass)
{ {
QList<FirmwarePluginFactory*> factoryList = FirmwarePluginFactoryRegister::instance()->pluginFactories(); QList<FirmwarePluginFactory*> factoryList = FirmwarePluginFactoryRegister::instance()->pluginFactories();
// Find the plugin which supports this vehicle // Find the plugin which supports this vehicle
for (int i=0; i<factoryList.count(); i++) { for (int i=0; i<factoryList.count(); i++) {
FirmwarePluginFactory* factory = factoryList[i]; FirmwarePluginFactory* factory = factoryList[i];
if (factory->supportedFirmwareTypes().contains(firmwareType)) { if (factory->supportedFirmwareClasses().contains(firmwareClass)) {
return factory; return factory;
} }
} }
......
...@@ -7,12 +7,7 @@ ...@@ -7,12 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef FirmwarePluginManager_H
#define FirmwarePluginManager_H
#include <QObject> #include <QObject>
...@@ -33,10 +28,10 @@ public: ...@@ -33,10 +28,10 @@ public:
~FirmwarePluginManager(); ~FirmwarePluginManager();
/// Returns list of firmwares which are supported by the system /// Returns list of firmwares which are supported by the system
QList<MAV_AUTOPILOT> supportedFirmwareTypes(void); QList<QGCMAVLink::FirmwareClass_t> supportedFirmwareClasses(void);
/// Returns the list of supported vehicle types for the specified firmware /// Returns the list of supported vehicle types for the specified firmware
QList<MAV_TYPE> supportedVehicleTypes(MAV_AUTOPILOT firmwareType); QList<QGCMAVLink::VehicleClass_t> supportedVehicleClasses(QGCMAVLink::FirmwareClass_t firmwareClass);
/// Returns appropriate plugin for autopilot type. /// Returns appropriate plugin for autopilot type.
/// @param firmwareType Type of firmwware to return plugin for. /// @param firmwareType Type of firmwware to return plugin for.
...@@ -45,10 +40,8 @@ public: ...@@ -45,10 +40,8 @@ public:
FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType); FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType);
private: private:
FirmwarePluginFactory* _findPluginFactory(MAV_AUTOPILOT firmwareType); FirmwarePluginFactory* _findPluginFactory(QGCMAVLink::FirmwareClass_t firmwareClass);
FirmwarePlugin* _genericFirmwarePlugin; FirmwarePlugin* _genericFirmwarePlugin;
QList<MAV_AUTOPILOT> _supportedFirmwareTypes; QList<QGCMAVLink::FirmwareClass_t> _supportedFirmwareClasses;
}; };
#endif
...@@ -297,23 +297,23 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) ...@@ -297,23 +297,23 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
return cmds; return cmds;
} }
QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const QString PX4FirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
{ {
switch (vehicleType) { switch (vehicleClass) {
case MAV_TYPE_GENERIC: case QGCMAVLink::VehicleClassGeneric:
return QStringLiteral(":/json/PX4-MavCmdInfoCommon.json"); return QStringLiteral(":/json/PX4-MavCmdInfoCommon.json");
case MAV_TYPE_FIXED_WING: case QGCMAVLink::VehicleClassFixedWing:
return QStringLiteral(":/json/PX4-MavCmdInfoFixedWing.json"); return QStringLiteral(":/json/PX4-MavCmdInfoFixedWing.json");
case MAV_TYPE_QUADROTOR: case QGCMAVLink::VehicleClassMultiRotor:
return QStringLiteral(":/json/PX4-MavCmdInfoMultiRotor.json"); return QStringLiteral(":/json/PX4-MavCmdInfoMultiRotor.json");
case MAV_TYPE_VTOL_QUADROTOR: case QGCMAVLink::VehicleClassVTOL:
return QStringLiteral(":/json/PX4-MavCmdInfoVTOL.json"); return QStringLiteral(":/json/PX4-MavCmdInfoVTOL.json");
case MAV_TYPE_SUBMARINE: case QGCMAVLink::VehicleClassSub:
return QStringLiteral(":/json/PX4-MavCmdInfoSub.json"); return QStringLiteral(":/json/PX4-MavCmdInfoSub.json");
case MAV_TYPE_GROUND_ROVER: case QGCMAVLink::VehicleClassRoverBoat:
return QStringLiteral(":/json/PX4-MavCmdInfoRover.json"); return QStringLiteral(":/json/PX4-MavCmdInfoRover.json");
default: default:
qWarning() << "PX4FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; qWarning() << "PX4FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
return QString(); return QString();
} }
} }
......
...@@ -55,7 +55,7 @@ public: ...@@ -55,7 +55,7 @@ public:
bool isGuidedMode (const Vehicle* vehicle) const override; bool isGuidedMode (const Vehicle* vehicle) const override;
void initializeVehicle (Vehicle* vehicle) override; void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override; bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); } QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); }
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override; FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
......
...@@ -7,10 +7,6 @@ ...@@ -7,10 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "PX4FirmwarePluginFactory.h" #include "PX4FirmwarePluginFactory.h"
#include "PX4/PX4FirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h"
...@@ -22,10 +18,10 @@ PX4FirmwarePluginFactory::PX4FirmwarePluginFactory(void) ...@@ -22,10 +18,10 @@ PX4FirmwarePluginFactory::PX4FirmwarePluginFactory(void)
} }
QList<MAV_AUTOPILOT> PX4FirmwarePluginFactory::supportedFirmwareTypes(void) const QList<QGCMAVLink::FirmwareClass_t> PX4FirmwarePluginFactory::supportedFirmwareClasses(void) const
{ {
QList<MAV_AUTOPILOT> list; QList<QGCMAVLink::FirmwareClass_t> list;
list.append(MAV_AUTOPILOT_PX4); list.append(QGCMAVLink::FirmwareClassPX4);
return list; return list;
} }
......
...@@ -7,8 +7,7 @@ ...@@ -7,8 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#ifndef PX4FirmwarePluginFactory_H #pragma once
#define PX4FirmwarePluginFactory_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
...@@ -21,11 +20,9 @@ class PX4FirmwarePluginFactory : public FirmwarePluginFactory ...@@ -21,11 +20,9 @@ class PX4FirmwarePluginFactory : public FirmwarePluginFactory
public: public:
PX4FirmwarePluginFactory(void); PX4FirmwarePluginFactory(void);
QList<MAV_AUTOPILOT> supportedFirmwareTypes (void) const final; QList<QGCMAVLink::FirmwareClass_t> supportedFirmwareClasses(void) const final;
FirmwarePlugin* firmwarePluginForAutopilot (MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) final; FirmwarePlugin* firmwarePluginForAutopilot (MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) final;
private: private:
PX4FirmwarePlugin* _pluginInstance; PX4FirmwarePlugin* _pluginInstance;
}; };
#endif
...@@ -26,8 +26,8 @@ FirstRunPrompt { ...@@ -26,8 +26,8 @@ FirstRunPrompt {
property var _offlineVehicle: QGroundControl.multiVehicleManager.offlineEditingVehicle property var _offlineVehicle: QGroundControl.multiVehicleManager.offlineEditingVehicle
property bool _showCruiseSpeed: !_offlineVehicle.multiRotor property bool _showCruiseSpeed: !_offlineVehicle.multiRotor
property bool _showHoverSpeed: _offlineVehicle.multiRotor || _offlineVehicle.vtol property bool _showHoverSpeed: _offlineVehicle.multiRotor || _offlineVehicle.vtol
property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 property bool _multipleFirmware: !QGroundControl.singleFirmwareSupport
property bool _multipleVehicleTypes: QGroundControl.supportedVehicleCount > 1 property bool _multipleVehicleTypes: !QGroundControl.singleVehicleSupport
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16
ColumnLayout { ColumnLayout {
...@@ -61,7 +61,7 @@ FirstRunPrompt { ...@@ -61,7 +61,7 @@ FirstRunPrompt {
} }
FactComboBox { FactComboBox {
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareClass
indexModel: false indexModel: false
visible: _multipleFirmware visible: _multipleFirmware
} }
...@@ -73,7 +73,7 @@ FirstRunPrompt { ...@@ -73,7 +73,7 @@ FirstRunPrompt {
} }
FactComboBox { FactComboBox {
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleClass
indexModel: false indexModel: false
visible: _multipleVehicleTypes visible: _multipleVehicleTypes
} }
......
...@@ -27,8 +27,7 @@ class MissionCommandList : public QObject ...@@ -27,8 +27,7 @@ class MissionCommandList : public QObject
Q_OBJECT Q_OBJECT
public: public:
/// @param jsonFilename Json file which contains commands /// @param baseCommandList true: bottomost level of mission command hierarchy (partial spec allowed), false: override level of hierarchy
/// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy
MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = nullptr); MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = nullptr);
/// Returns list of categories in this list /// Returns list of categories in this list
......
This diff is collapsed.
...@@ -7,8 +7,7 @@ ...@@ -7,8 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#ifndef MissionCommandTree_H #pragma once
#define MissionCommandTree_H
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
...@@ -26,9 +25,9 @@ class MissionCommandTreeTest; ...@@ -26,9 +25,9 @@ class MissionCommandTreeTest;
/// Manages a hierarchy of MissionCommandUIInfo. /// Manages a hierarchy of MissionCommandUIInfo.
/// ///
/// The static hierarchy allows for overriding mission command ui info based on MAV_AUTOPILOT and MAV_TYPE. The hierarchy of the tree is: /// The static hierarchy allows for overriding mission command ui info based on firmware and vehicle class. The hierarchy of the tree is:
/// Any Firmware, Any Vehicle - Base set of all command definitions for any firmware, any vehicle, essentially ui defined to mavlink spec /// FirmwareClassGeneric - VehicleClassGeneric - Base set of all command definitions for any firmware, any vehicle, ui defined by mavlink spec
/// Any Firmware, Fixed Wing /// FirmwareClassGeneric - VehicleClassFixedWing
/// Known Firmware, Fixed Wing /// Known Firmware, Fixed Wing
/// Any Firmware, Multi Rotor (all types) /// Any Firmware, Multi Rotor (all types)
/// Known Firmware, Multi Rotor (all types) /// Known Firmware, Multi Rotor (all types)
...@@ -62,19 +61,17 @@ public: ...@@ -62,19 +61,17 @@ public:
const MissionCommandUIInfo* getUIInfo(Vehicle* vehicle, MAV_CMD command); const MissionCommandUIInfo* getUIInfo(Vehicle* vehicle, MAV_CMD command);
/// @param showFlyThroughCommands - true: al commands shows, false: filter out commands which the vehicle flies through (specifiedCoordinate=true, standaloneCoordinate=false) /// @param showFlyThroughCommands - true: all commands shows, false: filter out commands which the vehicle flies through (specifiedCoordinate=true, standaloneCoordinate=false)
Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category, bool showFlyThroughCommands); Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category, bool showFlyThroughCommands);
// Overrides from QGCTool // Overrides from QGCTool
virtual void setToolbox(QGCToolbox* toolbox); virtual void setToolbox(QGCToolbox* toolbox);
private: private:
void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree); void _collapseHierarchy (const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree);
MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const; void _buildAllCommands (Vehicle* vehicle);
MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const; QStringList _availableCategoriesForVehicle (Vehicle* vehicle);
void _buildAllCommands(Vehicle* vehicle); void _firmwareAndVehicleClassInfo (Vehicle* vehicle, QGCMAVLink::FirmwareClass_t& firmwareClass, QGCMAVLink::VehicleClass_t& vehicleClass) const;
QStringList _availableCategoriesForVehicle(Vehicle* vehicle);
void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const;
private: private:
QString _allCommandsCategory; ///< Category which contains all available commands QString _allCommandsCategory; ///< Category which contains all available commands
...@@ -83,18 +80,16 @@ private: ...@@ -83,18 +80,16 @@ private:
bool _unitTest; ///< true: running in unit test mode bool _unitTest; ///< true: running in unit test mode
/// Full hierarchy /// Full hierarchy
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, MissionCommandList*>> _staticCommandTree; QMap<QGCMAVLink::FirmwareClass_t, QMap<QGCMAVLink::VehicleClass_t, MissionCommandList*>> _staticCommandTree;
/// Collapsed hierarchy for specific vehicle type /// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _allCommands; QMap<QGCMAVLink::FirmwareClass_t, QMap<QGCMAVLink::VehicleClass_t, QMap<MAV_CMD, MissionCommandUIInfo*>>> _allCommands;
/// Collapsed hierarchy for specific vehicle type /// Collapsed hierarchy for specific vehicle type
QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList /* category */>> _supportedCategories; QMap<QGCMAVLink::FirmwareClass_t, QMap<QGCMAVLink::VehicleClass_t, QStringList /* category */>> _supportedCategories;
#ifdef UNITTEST_BUILD #ifdef UNITTEST_BUILD
friend class MissionCommandTreeTest; friend class MissionCommandTreeTest;
#endif #endif
}; };
#endif
...@@ -725,16 +725,16 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -725,16 +725,16 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
// Get the firmware/vehicle type from the plan file // Get the firmware/vehicle type from the plan file
MAV_AUTOPILOT planFileFirmwareType = static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt()); MAV_AUTOPILOT planFileFirmwareType = static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt());
MAV_TYPE planFileVehicleType = static_cast<MAV_TYPE> (appSettings->offlineEditingVehicleType()->rawValue().toInt()); MAV_TYPE planFileVehicleType = static_cast<MAV_TYPE> (QGCMAVLink::vehicleClassToMavType(appSettings->offlineEditingVehicleClass()->rawValue().toInt()));
if (json.contains(_jsonVehicleTypeKey)) { if (json.contains(_jsonVehicleTypeKey)) {
planFileVehicleType = static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt()); planFileVehicleType = static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt());
} }
// Update firmware/vehicle offline settings if we aren't connect to a vehicle // Update firmware/vehicle offline settings if we aren't connect to a vehicle
if (_masterController->offline()) { if (_masterController->offline()) {
appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt()))); appSettings->offlineEditingFirmwareClass()->setRawValue(QGCMAVLink::firmwareClass(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
if (json.contains(_jsonVehicleTypeKey)) { if (json.contains(_jsonVehicleTypeKey)) {
appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt()))); appSettings->offlineEditingVehicleClass()->setRawValue(QGCMAVLink::vehicleClass(planFileVehicleType));
} }
} }
......
...@@ -50,7 +50,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) ...@@ -50,7 +50,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
_rgMissionControllerSignals[visualItemsChangedSignalIndex] = SIGNAL(visualItemsChanged()); _rgMissionControllerSignals[visualItemsChangedSignalIndex] = SIGNAL(visualItemsChanged());
// Master controller pulls offline vehicle info from settings // Master controller pulls offline vehicle info from settings
qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->setRawValue(firmwareType); qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareClass()->setRawValue(QGCMAVLink::firmwareClass(firmwareType));
_masterController = new PlanMasterController(this); _masterController = new PlanMasterController(this);
_masterController->setFlyView(false); _masterController->setFlyView(false);
_missionController = _masterController->missionController(); _missionController = _masterController->missionController();
......
...@@ -143,8 +143,8 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -143,8 +143,8 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
// Update controllerVehicle to the currently connected vehicle // Update controllerVehicle to the currently connected vehicle
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(_managerVehicle->firmwareType())); appSettings->offlineEditingFirmwareClass()->setRawValue(QGCMAVLink::firmwareClass(_managerVehicle->firmwareType()));
appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(_managerVehicle->vehicleType())); appSettings->offlineEditingVehicleClass()->setRawValue(QGCMAVLink::vehicleClass(_managerVehicle->vehicleType()));
// We use these signals to sequence upload and download to the multiple controller/managers // We use these signals to sequence upload and download to the multiple controller/managers
connect(_managerVehicle->missionManager(), &MissionManager::newMissionItemsAvailable, this, &PlanMasterController::_loadMissionComplete); connect(_managerVehicle->missionManager(), &MissionManager::newMissionItemsAvailable, this, &PlanMasterController::_loadMissionComplete);
......
...@@ -40,7 +40,6 @@ Rectangle { ...@@ -40,7 +40,6 @@ Rectangle {
property real _sectionSpacer: ScreenTools.defaultFontPixelWidth / 2 // spacing between section headings property real _sectionSpacer: ScreenTools.defaultFontPixelWidth / 2 // spacing between section headings
property bool _singleComplexItem: _missionController.complexMissionItemNames.length === 1 property bool _singleComplexItem: _missionController.complexMissionItemNames.length === 1
property bool _readyForSave: missionItem.readyForSaveState === VisualMissionItem.ReadyForSave property bool _readyForSave: missionItem.readyForSaveState === VisualMissionItem.ReadyForSave
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
readonly property real _editFieldWidth: Math.min(width - _innerMargin * 2, ScreenTools.defaultFontPixelWidth * 12) readonly property real _editFieldWidth: Math.min(width - _innerMargin * 2, ScreenTools.defaultFontPixelWidth * 12)
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2 readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2
...@@ -160,6 +159,7 @@ Rectangle { ...@@ -160,6 +159,7 @@ Rectangle {
id: commandDialog id: commandDialog
MissionCommandDialog { MissionCommandDialog {
vehicle: masterController.controllerVehicle
missionItem: _root.missionItem missionItem: _root.missionItem
map: _root.map map: _root.map
// FIXME: Disabling fly through commands doesn't work since you may need to change from an RTL to something else // FIXME: Disabling fly through commands doesn't work since you may need to change from an RTL to something else
...@@ -207,6 +207,8 @@ Rectangle { ...@@ -207,6 +207,8 @@ Rectangle {
visible: missionItem.specifiesCoordinate visible: missionItem.specifiesCoordinate
enabled: _activeVehicle enabled: _activeVehicle
onTriggered: missionItem.coordinate = _activeVehicle.coordinate onTriggered: missionItem.coordinate = _activeVehicle.coordinate
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
} }
QGCMenuItem { QGCMenuItem {
......
...@@ -26,8 +26,8 @@ Rectangle { ...@@ -26,8 +26,8 @@ Rectangle {
property bool _vehicleHasHomePosition: _controllerVehicle.homePosition.isValid property bool _vehicleHasHomePosition: _controllerVehicle.homePosition.isValid
property bool _showCruiseSpeed: !_controllerVehicle.multiRotor property bool _showCruiseSpeed: !_controllerVehicle.multiRotor
property bool _showHoverSpeed: _controllerVehicle.multiRotor || _controllerVehicle.vtol property bool _showHoverSpeed: _controllerVehicle.multiRotor || _controllerVehicle.vtol
property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 property bool _multipleFirmware: !QGroundControl.singleFirmwareSupport
property bool _multipleVehicleTypes: QGroundControl.supportedVehicleCount > 1 property bool _multipleVehicleTypes: !QGroundControl.singleVehicleSupport
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16
property bool _mobile: ScreenTools.isMobile property bool _mobile: ScreenTools.isMobile
property var _savePath: QGroundControl.settingsManager.appSettings.missionSavePath property var _savePath: QGroundControl.settingsManager.appSettings.missionSavePath
...@@ -194,7 +194,7 @@ Rectangle { ...@@ -194,7 +194,7 @@ Rectangle {
visible: _multipleFirmware visible: _multipleFirmware
} }
FactComboBox { FactComboBox {
fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareClass
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleFirmware && _noMissionItemsAdded visible: _multipleFirmware && _noMissionItemsAdded
...@@ -210,7 +210,7 @@ Rectangle { ...@@ -210,7 +210,7 @@ Rectangle {
visible: _multipleVehicleTypes visible: _multipleVehicleTypes
} }
FactComboBox { FactComboBox {
fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleClass
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleVehicleTypes && _noMissionItemsAdded visible: _multipleVehicleTypes && _noMissionItemsAdded
......
...@@ -19,12 +19,11 @@ import QGroundControl.Palette 1.0 ...@@ -19,12 +19,11 @@ import QGroundControl.Palette 1.0
QGCViewDialog { QGCViewDialog {
id: root id: root
property var vehicle
property var missionItem property var missionItem
property var map property var map
property bool flyThroughCommandsAllowed property bool flyThroughCommandsAllowed
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
QGCLabel { QGCLabel {
...@@ -38,10 +37,10 @@ QGCViewDialog { ...@@ -38,10 +37,10 @@ QGCViewDialog {
anchors.margins: ScreenTools.defaultFontPixelWidth anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: categoryLabel.right anchors.left: categoryLabel.right
anchors.right: parent.right anchors.right: parent.right
model: QGroundControl.missionCommandTree.categoriesForVehicle(_vehicle) model: QGroundControl.missionCommandTree.categoriesForVehicle(vehicle)
function categorySelected(category) { function categorySelected(category) {
commandList.model = QGroundControl.missionCommandTree.getCommandsForCategory(_vehicle, category, flyThroughCommandsAllowed) commandList.model = QGroundControl.missionCommandTree.getCommandsForCategory(vehicle, category, flyThroughCommandsAllowed)
} }
Component.onCompleted: { Component.onCompleted: {
......
...@@ -190,31 +190,28 @@ void QGroundControlQmlGlobal::setMavlinkSystemID(int id) ...@@ -190,31 +190,28 @@ void QGroundControlQmlGlobal::setMavlinkSystemID(int id)
emit mavlinkSystemIDChanged(id); emit mavlinkSystemIDChanged(id);
} }
int QGroundControlQmlGlobal::supportedFirmwareCount() bool QGroundControlQmlGlobal::singleFirmwareSupport(void)
{ {
return _firmwarePluginManager->supportedFirmwareTypes().count(); return _firmwarePluginManager->supportedFirmwareClasses().count() == 1;
} }
int QGroundControlQmlGlobal::supportedVehicleCount() bool QGroundControlQmlGlobal::singleVehicleSupport(void)
{ {
int count = 0; if (singleFirmwareSupport()) {
QList<MAV_AUTOPILOT> list = _firmwarePluginManager->supportedFirmwareTypes(); return _firmwarePluginManager->supportedVehicleClasses(_firmwarePluginManager->supportedFirmwareClasses()[0]).count() == 1;
foreach(auto firmware, list) {
if(firmware != MAV_AUTOPILOT_GENERIC) {
count += _firmwarePluginManager->supportedVehicleTypes(firmware).count();
}
} }
return count;
return false;
} }
bool QGroundControlQmlGlobal::px4ProFirmwareSupported() bool QGroundControlQmlGlobal::px4ProFirmwareSupported()
{ {
return _firmwarePluginManager->supportedFirmwareTypes().contains(MAV_AUTOPILOT_PX4); return _firmwarePluginManager->supportedFirmwareClasses().contains(QGCMAVLink::FirmwareClassPX4);
} }
bool QGroundControlQmlGlobal::apmFirmwareSupported() bool QGroundControlQmlGlobal::apmFirmwareSupported()
{ {
return _firmwarePluginManager->supportedFirmwareTypes().contains(MAV_AUTOPILOT_ARDUPILOTMEGA); return _firmwarePluginManager->supportedFirmwareClasses().contains(QGCMAVLink::FirmwareClassArduPilot);
} }
bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B) bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
......
...@@ -7,12 +7,7 @@ ...@@ -7,12 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef QGroundControlQmlGlobal_H
#define QGroundControlQmlGlobal_H
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "QGCApplication.h" #include "QGCApplication.h"
...@@ -62,35 +57,41 @@ public: ...@@ -62,35 +57,41 @@ public:
}; };
Q_ENUM(AltitudeMode) Q_ENUM(AltitudeMode)
Q_PROPERTY(QString appName READ appName CONSTANT) Q_PROPERTY(QString appName READ appName CONSTANT)
Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT)
Q_PROPERTY(LinkManager* linkManager READ linkManager CONSTANT) Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT)
Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager CONSTANT) Q_PROPERTY(QGCMapEngineManager* mapEngineManager READ mapEngineManager CONSTANT)
Q_PROPERTY(QGCMapEngineManager* mapEngineManager READ mapEngineManager CONSTANT) Q_PROPERTY(QGCPositionManager* qgcPositionManger READ qgcPositionManger CONSTANT)
Q_PROPERTY(QGCPositionManager* qgcPositionManger READ qgcPositionManger CONSTANT) Q_PROPERTY(VideoManager* videoManager READ videoManager CONSTANT)
Q_PROPERTY(MissionCommandTree* missionCommandTree READ missionCommandTree CONSTANT) Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT)
Q_PROPERTY(VideoManager* videoManager READ videoManager CONSTANT) Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT)
Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT) Q_PROPERTY(AirspaceManager* airspaceManager READ airspaceManager CONSTANT)
Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT) Q_PROPERTY(ADSBVehicleManager* adsbVehicleManager READ adsbVehicleManager CONSTANT)
Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT) Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT)
Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT) Q_PROPERTY(MissionCommandTree* missionCommandTree READ missionCommandTree CONSTANT)
Q_PROPERTY(AirspaceManager* airspaceManager READ airspaceManager CONSTANT) Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT)
Q_PROPERTY(ADSBVehicleManager* adsbVehicleManager READ adsbVehicleManager CONSTANT) Q_PROPERTY(bool airmapSupported READ airmapSupported CONSTANT)
Q_PROPERTY(bool airmapSupported READ airmapSupported CONSTANT) Q_PROPERTY(TaisyncManager* taisyncManager READ taisyncManager CONSTANT)
Q_PROPERTY(TaisyncManager* taisyncManager READ taisyncManager CONSTANT) Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT)
Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT) Q_PROPERTY(MicrohardManager* microhardManager READ microhardManager CONSTANT)
Q_PROPERTY(MicrohardManager* microhardManager READ microhardManager CONSTANT) Q_PROPERTY(bool microhardSupported READ microhardSupported CONSTANT)
Q_PROPERTY(bool microhardSupported READ microhardSupported CONSTANT) Q_PROPERTY(bool supportsPairing READ supportsPairing CONSTANT)
Q_PROPERTY(bool supportsPairing READ supportsPairing CONSTANT) Q_PROPERTY(QGCPalette* globalPalette MEMBER _globalPalette CONSTANT) ///< This palette will always return enabled colors
Q_PROPERTY(QGCPalette* globalPalette MEMBER _globalPalette CONSTANT) // This palette will always return enabled colors Q_PROPERTY(QmlUnitsConversion* unitsConversion READ unitsConversion CONSTANT)
Q_PROPERTY(QmlUnitsConversion* unitsConversion READ unitsConversion CONSTANT) Q_PROPERTY(bool singleFirmwareSupport READ singleFirmwareSupport CONSTANT)
#if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(bool singleVehicleSupport READ singleVehicleSupport CONSTANT)
Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) Q_PROPERTY(bool px4ProFirmwareSupported READ px4ProFirmwareSupported CONSTANT)
#endif Q_PROPERTY(int apmFirmwareSupported READ apmFirmwareSupported CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT) Q_PROPERTY(QGeoCoordinate flightMapPosition READ flightMapPosition WRITE setFlightMapPosition NOTIFY flightMapPositionChanged)
Q_PROPERTY(int supportedVehicleCount READ supportedVehicleCount CONSTANT) Q_PROPERTY(double flightMapZoom READ flightMapZoom WRITE setFlightMapZoom NOTIFY flightMapZoomChanged)
Q_PROPERTY(bool px4ProFirmwareSupported READ px4ProFirmwareSupported CONSTANT) Q_PROPERTY(double flightMapInitialZoom MEMBER _flightMapInitialZoom CONSTANT) ///< Zoom level to use when either gcs or vehicle shows up for first time
Q_PROPERTY(int apmFirmwareSupported READ apmFirmwareSupported CONSTANT)
Q_PROPERTY(QString parameterFileExtension READ parameterFileExtension CONSTANT)
Q_PROPERTY(QString missionFileExtension READ missionFileExtension CONSTANT)
Q_PROPERTY(QString telemetryFileExtension READ telemetryFileExtension CONSTANT)
Q_PROPERTY(QString qgcVersion READ qgcVersion CONSTANT)
Q_PROPERTY(bool skipSetupPage READ skipSetupPage WRITE setSkipSetupPage NOTIFY skipSetupPageChanged)
Q_PROPERTY(qreal zOrderTopMost READ zOrderTopMost CONSTANT) ///< z order for top most items, toolbar, main window sub view 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 Q_PROPERTY(qreal zOrderWidgets READ zOrderWidgets CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
...@@ -99,7 +100,6 @@ public: ...@@ -99,7 +100,6 @@ public:
Q_PROPERTY(qreal zOrderWaypointIndicators READ zOrderWaypointIndicators CONSTANT) Q_PROPERTY(qreal zOrderWaypointIndicators READ zOrderWaypointIndicators CONSTANT)
Q_PROPERTY(qreal zOrderTrajectoryLines READ zOrderTrajectoryLines CONSTANT) Q_PROPERTY(qreal zOrderTrajectoryLines READ zOrderTrajectoryLines CONSTANT)
Q_PROPERTY(qreal zOrderWaypointLines READ zOrderWaypointLines CONSTANT) Q_PROPERTY(qreal zOrderWaypointLines READ zOrderWaypointLines CONSTANT)
//------------------------------------------------------------------------- //-------------------------------------------------------------------------
// MavLink Protocol // MavLink Protocol
Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged) Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged)
...@@ -107,16 +107,10 @@ public: ...@@ -107,16 +107,10 @@ public:
Q_PROPERTY(bool hasAPMSupport READ hasAPMSupport CONSTANT) Q_PROPERTY(bool hasAPMSupport READ hasAPMSupport CONSTANT)
Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT) Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT)
Q_PROPERTY(QGeoCoordinate flightMapPosition READ flightMapPosition WRITE setFlightMapPosition NOTIFY flightMapPositionChanged)
Q_PROPERTY(double flightMapZoom READ flightMapZoom WRITE setFlightMapZoom NOTIFY flightMapZoomChanged)
Q_PROPERTY(double flightMapInitialZoom MEMBER _flightMapInitialZoom CONSTANT) ///< Zoom level to use when either gcs or vehicle shows up for first time
Q_PROPERTY(QString parameterFileExtension READ parameterFileExtension CONSTANT)
Q_PROPERTY(QString missionFileExtension READ missionFileExtension CONSTANT)
Q_PROPERTY(QString telemetryFileExtension READ telemetryFileExtension CONSTANT)
Q_PROPERTY(QString qgcVersion READ qgcVersion CONSTANT) #if defined(QGC_ENABLE_PAIRING)
Q_PROPERTY(bool skipSetupPage READ skipSetupPage WRITE setSkipSetupPage NOTIFY skipSetupPageChanged) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT)
#endif
Q_INVOKABLE void saveGlobalSetting (const QString& key, const QString& value); Q_INVOKABLE void saveGlobalSetting (const QString& key, const QString& value);
Q_INVOKABLE QString loadGlobalSetting (const QString& key, const QString& defaultValue); Q_INVOKABLE QString loadGlobalSetting (const QString& key, const QString& defaultValue);
...@@ -212,8 +206,8 @@ public: ...@@ -212,8 +206,8 @@ public:
bool hasMAVLinkInspector () { return false; } bool hasMAVLinkInspector () { return false; }
#endif #endif
int supportedFirmwareCount (); bool singleFirmwareSupport ();
int supportedVehicleCount (); bool singleVehicleSupport ();
bool px4ProFirmwareSupported (); bool px4ProFirmwareSupported ();
bool apmFirmwareSupported (); bool apmFirmwareSupported ();
bool skipSetupPage () { return _skipSetupPage; } bool skipSetupPage () { return _skipSetupPage; }
...@@ -281,5 +275,3 @@ private: ...@@ -281,5 +275,3 @@ private:
static QGeoCoordinate _coord; static QGeoCoordinate _coord;
static double _zoom; static double _zoom;
}; };
#endif
...@@ -4,19 +4,19 @@ ...@@ -4,19 +4,19 @@
"QGC.MetaData.Facts": "QGC.MetaData.Facts":
[ [
{ {
"name": "offlineEditingFirmwareType", "name": "offlineEditingFirmwareClass",
"shortDescription": "Offline editing firmware type", "shortDescription": "Offline editing firmware class",
"type": "uint32", "type": "uint32",
"enumStrings": "ArduPilot,PX4 Pro,Mavlink Generic", "enumStrings": "ArduPilot,PX4 Pro,Mavlink Generic",
"enumValues": "3,12,0", "enumValues": "3,12,0",
"defaultValue": 12 "defaultValue": 12
}, },
{ {
"name": "offlineEditingVehicleType", "name": "offlineEditingVehicleClass",
"shortDescription": "Offline editing vehicle type", "shortDescription": "Offline editing vehicle class",
"type": "uint32", "type": "uint32",
"enumStrings": "Fixed Wing,Multi-Rotor,VTOL,Rover,Sub", "enumStrings": "Fixed Wing,Multi-Rotor,VTOL,Rover,Sub,Mavlink Generic",
"enumValues": "1,2,20,10,12", "enumValues": "1,2,20,10,12,0",
"defaultValue": 2 "defaultValue": 2
}, },
{ {
......
...@@ -39,13 +39,26 @@ DECLARE_SETTINGGROUP(App, "") ...@@ -39,13 +39,26 @@ DECLARE_SETTINGGROUP(App, "")
qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only"); qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only");
QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light); QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light);
// virtualJoystickCentralized -> virtualJoystickAutoCenterThrottle
QSettings settings; QSettings settings;
// These two "type" keys were changed to "class" values
static const char* deprecatedFirmwareTypeKey = "offlineEditingFirmwareType";
static const char* deprecatedVehicleTypeKey = "offlineEditingVehicleType";
if (settings.contains(deprecatedFirmwareTypeKey)) {
settings.setValue(deprecatedFirmwareTypeKey, QGCMAVLink::firmwareClass(static_cast<MAV_AUTOPILOT>(settings.value(deprecatedFirmwareTypeKey).toInt())));
}
if (settings.contains(deprecatedVehicleTypeKey)) {
settings.setValue(deprecatedVehicleTypeKey, QGCMAVLink::vehicleClass(static_cast<MAV_TYPE>(settings.value(deprecatedVehicleTypeKey).toInt())));
}
QStringList deprecatedKeyNames = { "virtualJoystickCentralized", "offlineEditingFirmwareType", "offlineEditingVehicleType" };
QStringList newKeyNames = { "virtualJoystickAutoCenterThrottle", "offlineEditingFirmwareClass", "offlineEditingVehicleClass" };
settings.beginGroup(_settingsGroup); settings.beginGroup(_settingsGroup);
QString deprecatedVirtualJoystickCentralizedKey("virtualJoystickCentralized"); for (int i=0; i<deprecatedKeyNames.count(); i++) {
if (settings.contains(deprecatedVirtualJoystickCentralizedKey)) { if (settings.contains(deprecatedKeyNames[i])) {
settings.setValue(virtualJoystickAutoCenterThrottleName, settings.value(deprecatedVirtualJoystickCentralizedKey)); settings.setValue(newKeyNames[i], settings.value(deprecatedKeyNames[i]));
settings.remove(deprecatedVirtualJoystickCentralizedKey); settings.remove(deprecatedKeyNames[i]);
}
} }
// Instantiate savePath so we can check for override and setup default path if needed // Instantiate savePath so we can check for override and setup default path if needed
...@@ -85,8 +98,8 @@ DECLARE_SETTINGGROUP(App, "") ...@@ -85,8 +98,8 @@ DECLARE_SETTINGGROUP(App, "")
connect(languageFact, &Fact::rawValueChanged, this, &AppSettings::_languageChanged); connect(languageFact, &Fact::rawValueChanged, this, &AppSettings::_languageChanged);
} }
DECLARE_SETTINGSFACT(AppSettings, offlineEditingFirmwareType) DECLARE_SETTINGSFACT(AppSettings, offlineEditingFirmwareClass)
DECLARE_SETTINGSFACT(AppSettings, offlineEditingVehicleType) DECLARE_SETTINGSFACT(AppSettings, offlineEditingVehicleClass)
DECLARE_SETTINGSFACT(AppSettings, offlineEditingCruiseSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingCruiseSpeed)
DECLARE_SETTINGSFACT(AppSettings, offlineEditingHoverSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingHoverSpeed)
DECLARE_SETTINGSFACT(AppSettings, offlineEditingAscentSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingAscentSpeed)
...@@ -216,29 +229,6 @@ QString AppSettings::crashSavePath(void) ...@@ -216,29 +229,6 @@ QString AppSettings::crashSavePath(void)
return QString(); return QString();
} }
MAV_AUTOPILOT AppSettings::offlineEditingFirmwareTypeFromFirmwareType(MAV_AUTOPILOT firmwareType)
{
if (firmwareType != MAV_AUTOPILOT_PX4 && firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {
firmwareType = MAV_AUTOPILOT_GENERIC;
}
return firmwareType;
}
MAV_TYPE AppSettings::offlineEditingVehicleTypeFromVehicleType(MAV_TYPE vehicleType)
{
if (QGCMAVLink::isRover(vehicleType)) {
return MAV_TYPE_GROUND_ROVER;
} else if (QGCMAVLink::isSub(vehicleType)) {
return MAV_TYPE_SUBMARINE;
} else if (QGCMAVLink::isVTOL(vehicleType)) {
return MAV_TYPE_VTOL_QUADROTOR;
} else if (QGCMAVLink::isFixedWing(vehicleType)) {
return MAV_TYPE_FIXED_WING;
} else {
return MAV_TYPE_QUADROTOR;
}
}
QList<int> AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRunPromptIds) QList<int> AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRunPromptIds)
{ {
QList<int> rgIds; QList<int> rgIds;
......
...@@ -26,8 +26,8 @@ public: ...@@ -26,8 +26,8 @@ public:
DEFINE_SETTING_NAME_GROUP() DEFINE_SETTING_NAME_GROUP()
DEFINE_SETTINGFACT(offlineEditingFirmwareType) DEFINE_SETTINGFACT(offlineEditingFirmwareClass)
DEFINE_SETTINGFACT(offlineEditingVehicleType) DEFINE_SETTINGFACT(offlineEditingVehicleClass)
DEFINE_SETTINGFACT(offlineEditingCruiseSpeed) DEFINE_SETTINGFACT(offlineEditingCruiseSpeed)
DEFINE_SETTINGFACT(offlineEditingHoverSpeed) DEFINE_SETTINGFACT(offlineEditingHoverSpeed)
DEFINE_SETTINGFACT(offlineEditingAscentSpeed) DEFINE_SETTINGFACT(offlineEditingAscentSpeed)
...@@ -94,9 +94,6 @@ public: ...@@ -94,9 +94,6 @@ public:
static QVariant firstRunPromptsIdsListToVariant (const QList<int>& rgIds); static QVariant firstRunPromptsIdsListToVariant (const QList<int>& rgIds);
Q_INVOKABLE void firstRunPromptIdsMarkIdAsShown (int id); Q_INVOKABLE void firstRunPromptIdsMarkIdAsShown (int id);
static MAV_AUTOPILOT offlineEditingFirmwareTypeFromFirmwareType (MAV_AUTOPILOT firmwareType);
static MAV_TYPE offlineEditingVehicleTypeFromVehicleType (MAV_TYPE vehicleType);
// Application wide file extensions // Application wide file extensions
static const char* parameterFileExtension; static const char* parameterFileExtension;
static const char* planFileExtension; static const char* planFileExtension;
......
...@@ -103,7 +103,7 @@ bool CompInfoParam::_isParameterVolatile(const QString& name) ...@@ -103,7 +103,7 @@ bool CompInfoParam::_isParameterVolatile(const QString& name)
FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType) FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType)
{ {
FirmwarePluginManager* pluginMgr = qgcApp()->toolbox()->firmwarePluginManager(); FirmwarePluginManager* pluginMgr = qgcApp()->toolbox()->firmwarePluginManager();
MAV_TYPE anySupportedVehicleType = pluginMgr->supportedVehicleTypes(firmwareType)[0]; MAV_TYPE anySupportedVehicleType = QGCMAVLink::vehicleClassToMavType(pluginMgr->supportedVehicleClasses(QGCMAVLink::firmwareClass(firmwareType))[0]);
return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType); return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType);
} }
......
...@@ -424,17 +424,17 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -424,17 +424,17 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
void Vehicle::trackFirmwareVehicleTypeChanges(void) void Vehicle::trackFirmwareVehicleTypeChanges(void)
{ {
connect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged); connect(_settingsManager->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged); connect(_settingsManager->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
_offlineFirmwareTypeSettingChanged(_settingsManager->appSettings()->offlineEditingFirmwareType()->rawValue()); _offlineFirmwareTypeSettingChanged(_settingsManager->appSettings()->offlineEditingFirmwareClass()->rawValue());
_offlineVehicleTypeSettingChanged(_settingsManager->appSettings()->offlineEditingVehicleType()->rawValue()); _offlineVehicleTypeSettingChanged(_settingsManager->appSettings()->offlineEditingVehicleClass()->rawValue());
} }
void Vehicle::stopTrackingFirmwareVehicleTypeChanges(void) void Vehicle::stopTrackingFirmwareVehicleTypeChanges(void)
{ {
disconnect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged); disconnect(_settingsManager->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
disconnect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged); disconnect(_settingsManager->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
} }
void Vehicle::_commonInit() void Vehicle::_commonInit()
...@@ -588,9 +588,9 @@ void Vehicle::prepareDelete() ...@@ -588,9 +588,9 @@ void Vehicle::prepareDelete()
} }
} }
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value) void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
{ {
_firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt()); _firmwareType = static_cast<MAV_AUTOPILOT>(varFirmwareType.toInt());
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) { if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN; _capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
...@@ -601,9 +601,9 @@ void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value) ...@@ -601,9 +601,9 @@ void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
emit capabilityBitsChanged(_capabilityBits); emit capabilityBitsChanged(_capabilityBits);
} }
void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value) void Vehicle::_offlineVehicleTypeSettingChanged(QVariant varVehicleType)
{ {
_vehicleType = static_cast<MAV_TYPE>(value.toInt()); _vehicleType = static_cast<MAV_TYPE>(varVehicleType.toInt());
emit vehicleTypeChanged(); emit vehicleTypeChanged();
} }
...@@ -2721,7 +2721,7 @@ bool Vehicle::fixedWing() const ...@@ -2721,7 +2721,7 @@ bool Vehicle::fixedWing() const
bool Vehicle::rover() const bool Vehicle::rover() const
{ {
return QGCMAVLink::isRover(vehicleType()); return QGCMAVLink::isRoverBoat(vehicleType());
} }
bool Vehicle::sub() const bool Vehicle::sub() const
...@@ -2736,7 +2736,7 @@ bool Vehicle::multiRotor() const ...@@ -2736,7 +2736,7 @@ bool Vehicle::multiRotor() const
bool Vehicle::vtol() const bool Vehicle::vtol() const
{ {
return _firmwarePlugin->isVtol(this); return QGCMAVLink::isVTOL(vehicleType());
} }
bool Vehicle::supportsThrottleModeCenterZero() const bool Vehicle::supportsThrottleModeCenterZero() const
......
...@@ -1159,8 +1159,8 @@ public: ...@@ -1159,8 +1159,8 @@ public:
public slots: public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight); void setVtolInFwdFlight (bool vtolInFwdFlight);
void _offlineFirmwareTypeSettingChanged (QVariant value); // Should only be used by MissionControler to set firmware from Plan file void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
void _offlineVehicleTypeSettingChanged (QVariant value); // Should only be used by MissionController to set vehicle type from Plan file void _offlineVehicleTypeSettingChanged (QVariant varVehicleType); // Should only be used by MissionController to set vehicle type from Plan file
signals: signals:
void allLinksInactive (Vehicle* vehicle); void allLinksInactive (Vehicle* vehicle);
......
...@@ -9,45 +9,91 @@ ...@@ -9,45 +9,91 @@
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
bool QGCMAVLink::isFixedWing(MAV_TYPE mavType) constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassPX4;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassArduPilot;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassGeneric;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassFixedWing;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassRoverBoat;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassSub;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassMultiRotor;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassVTOL;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassGeneric;
QList<QGCMAVLink::FirmwareClass_t> QGCMAVLink::allFirmwareClasses(void)
{ {
return mavType == MAV_TYPE_FIXED_WING; static const QList<QGCMAVLink::FirmwareClass_t> classes = {
FirmwareClassPX4,
FirmwareClassArduPilot,
FirmwareClassGeneric
};
return classes;
} }
bool QGCMAVLink::isRover(MAV_TYPE mavType) QList<QGCMAVLink::VehicleClass_t> QGCMAVLink::allVehicleClasses(void)
{ {
switch (mavType) { static const QList<QGCMAVLink::VehicleClass_t> classes = {
case MAV_TYPE_GROUND_ROVER: VehicleClassFixedWing,
case MAV_TYPE_SURFACE_BOAT: VehicleClassRoverBoat,
return true; VehicleClassSub,
default: VehicleClassMultiRotor,
return false; VehicleClassVTOL,
VehicleClassGeneric,
};
return classes;
}
QGCMAVLink::FirmwareClass_t QGCMAVLink::firmwareClass(MAV_AUTOPILOT autopilot)
{
if (isPX4FirmwareClass(autopilot)) {
return FirmwareClassPX4;
} else if (isArduPilotFirmwareClass(autopilot)) {
return FirmwareClassArduPilot;
} else {
return FirmwareClassGeneric;
} }
} }
bool QGCMAVLink::isFixedWing(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassFixedWing;
}
bool QGCMAVLink::isRoverBoat(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassRoverBoat;
}
bool QGCMAVLink::isSub(MAV_TYPE mavType) bool QGCMAVLink::isSub(MAV_TYPE mavType)
{ {
return mavType == MAV_TYPE_SUBMARINE; return vehicleClass(mavType) == VehicleClassSub;
} }
bool QGCMAVLink::isMultiRotor(MAV_TYPE mavType) bool QGCMAVLink::isMultiRotor(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassMultiRotor;
}
bool QGCMAVLink::isVTOL(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassVTOL;
}
QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType)
{ {
switch (mavType) { switch (mavType) {
case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT:
return VehicleClassRoverBoat;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_HELICOPTER:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
return true; return VehicleClassMultiRotor;
default:
return false;
}
}
bool QGCMAVLink::isVTOL(MAV_TYPE mavType)
{
switch (mavType) {
case MAV_TYPE_VTOL_DUOROTOR: case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR: case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_TILTROTOR:
...@@ -55,29 +101,14 @@ bool QGCMAVLink::isVTOL(MAV_TYPE mavType) ...@@ -55,29 +101,14 @@ bool QGCMAVLink::isVTOL(MAV_TYPE mavType)
case MAV_TYPE_VTOL_RESERVED3: case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4: case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_VTOL_RESERVED5:
return true; return VehicleClassVTOL;
case MAV_TYPE_FIXED_WING:
return VehicleClassFixedWing;
default: default:
return false; return VehicleClassGeneric;
} }
} }
MAV_TYPE QGCMAVLink::vehicleClass(MAV_TYPE mavType)
{
if (isFixedWing(mavType)) {
return MAV_TYPE_FIXED_WING;
} else if (isRover(mavType)) {
return MAV_TYPE_GROUND_ROVER;
} else if (isSub(mavType)) {
return MAV_TYPE_SUBMARINE;
} else if (isMultiRotor(mavType)) {
return MAV_TYPE_QUADROTOR;
} else if (isVTOL(mavType)) {
return MAV_TYPE_VTOL_QUADROTOR;
}
return MAV_TYPE_GENERIC;
}
QString QGCMAVLink::mavResultToString(MAV_RESULT result) QString QGCMAVLink::mavResultToString(MAV_RESULT result)
{ {
switch (result) { switch (result) {
......
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#pragma once #pragma once
#include <QString> #include <QString>
#include <QList>
#define MAVLINK_USE_MESSAGE_INFO #define MAVLINK_USE_MESSAGE_INFO
#define MAVLINK_EXTERNAL_RX_STATUS // Single m_mavlink_status instance is in QGCApplication.cc #define MAVLINK_EXTERNAL_RX_STATUS // Single m_mavlink_status instance is in QGCApplication.cc
...@@ -48,13 +49,37 @@ extern mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; ...@@ -48,13 +49,37 @@ extern mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
class QGCMAVLink { class QGCMAVLink {
public: public:
static bool isFixedWing (MAV_TYPE mavType); typedef int FirmwareClass_t;
static bool isRover (MAV_TYPE mavType); typedef int VehicleClass_t;
static bool isSub (MAV_TYPE mavType);
static bool isMultiRotor (MAV_TYPE mavType); static constexpr FirmwareClass_t FirmwareClassPX4 = MAV_AUTOPILOT_PX4;
static bool isVTOL (MAV_TYPE mavType); static constexpr FirmwareClass_t FirmwareClassArduPilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
static MAV_TYPE vehicleClass (MAV_TYPE mavType); static constexpr FirmwareClass_t FirmwareClassGeneric = MAV_AUTOPILOT_GENERIC;
static QString mavResultToString (MAV_RESULT result);
static constexpr VehicleClass_t VehicleClassFixedWing = MAV_TYPE_FIXED_WING;
static constexpr VehicleClass_t VehicleClassRoverBoat = MAV_TYPE_GROUND_ROVER;
static constexpr VehicleClass_t VehicleClassSub = MAV_TYPE_SUBMARINE;
static constexpr VehicleClass_t VehicleClassMultiRotor = MAV_TYPE_QUADROTOR;
static constexpr VehicleClass_t VehicleClassVTOL = MAV_TYPE_VTOL_QUADROTOR;
static constexpr VehicleClass_t VehicleClassGeneric = MAV_TYPE_GENERIC;
static bool isPX4FirmwareClass (MAV_AUTOPILOT autopilot) { return autopilot == MAV_AUTOPILOT_PX4; }
static bool isArduPilotFirmwareClass(MAV_AUTOPILOT autopilot) { return autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA; }
static bool isGenericFirmwareClass (MAV_AUTOPILOT autopilot) { return !isPX4FirmwareClass(autopilot) && ! isArduPilotFirmwareClass(autopilot); }
static FirmwareClass_t firmwareClass (MAV_AUTOPILOT autopilot);
static MAV_AUTOPILOT firmwareClassToAutopilot(FirmwareClass_t firmwareClass) { return static_cast<MAV_AUTOPILOT>(firmwareClass); }
static QList<FirmwareClass_t> allFirmwareClasses (void);
static bool isFixedWing (MAV_TYPE mavType);
static bool isRoverBoat (MAV_TYPE mavType);
static bool isSub (MAV_TYPE mavType);
static bool isMultiRotor (MAV_TYPE mavType);
static bool isVTOL (MAV_TYPE mavType);
static VehicleClass_t vehicleClass (MAV_TYPE mavType);
static MAV_TYPE vehicleClassToMavType (VehicleClass_t vehicleClass) { return static_cast<MAV_TYPE>(vehicleClass); }
static QList<VehicleClass_t> allVehicleClasses (void);
static QString mavResultToString (MAV_RESULT result);
}; };
class MavlinkFTP { class MavlinkFTP {
......
...@@ -110,8 +110,8 @@ void UnitTest::init(void) ...@@ -110,8 +110,8 @@ void UnitTest::init(void)
// Force offline vehicle back to defaults // Force offline vehicle back to defaults
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
appSettings->offlineEditingFirmwareType()->setRawValue(appSettings->offlineEditingFirmwareType()->rawDefaultValue()); appSettings->offlineEditingFirmwareClass()->setRawValue(appSettings->offlineEditingFirmwareClass()->rawDefaultValue());
appSettings->offlineEditingVehicleType()->setRawValue(appSettings->offlineEditingVehicleType()->rawDefaultValue()); appSettings->offlineEditingVehicleClass()->setRawValue(appSettings->offlineEditingVehicleClass()->rawDefaultValue());
_messageBoxRespondedTo = false; _messageBoxRespondedTo = false;
_missedMessageBoxCount = 0; _missedMessageBoxCount = 0;
......
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