Commit f10e77cb authored by Don Gagne's avatar Don Gagne

Merge pull request #1800 from DonLakeFlyer/MultiVehicleManager

New MultiVehicleManager, Vehicle objects
parents a8a115f2 ed2bcaa0
...@@ -260,7 +260,6 @@ HEADERS += \ ...@@ -260,7 +260,6 @@ HEADERS += \
src/QmlControls/ParameterEditorController.h \ src/QmlControls/ParameterEditorController.h \
src/QmlControls/ScreenToolsController.h \ src/QmlControls/ScreenToolsController.h \
src/SerialPortIds.h \ src/SerialPortIds.h \
src/uas/QGCMAVLinkUASFactory.h \
src/uas/FileManager.h \ src/uas/FileManager.h \
src/uas/UAS.h \ src/uas/UAS.h \
src/uas/UASInterface.h \ src/uas/UASInterface.h \
...@@ -394,7 +393,6 @@ SOURCES += \ ...@@ -394,7 +393,6 @@ SOURCES += \
src/QmlControls/MavManager.cc \ src/QmlControls/MavManager.cc \
src/QmlControls/ParameterEditorController.cc \ src/QmlControls/ParameterEditorController.cc \
src/QmlControls/ScreenToolsController.cc \ src/QmlControls/ScreenToolsController.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/uas/FileManager.cc \ src/uas/FileManager.cc \
src/uas/UAS.cc \ src/uas/UAS.cc \
src/uas/UASManager.cc \ src/uas/UASManager.cc \
...@@ -559,15 +557,12 @@ SOURCES += \ ...@@ -559,15 +557,12 @@ SOURCES += \
# #
INCLUDEPATH += \ INCLUDEPATH += \
src/AutoPilotPlugins/PX4 \
src/FirmwarePlugin \ src/FirmwarePlugin \
src/Vehicle \
src/VehicleSetup \ src/VehicleSetup \
src/AutoPilotPlugins/PX4 \
HEADERS+= \ HEADERS+= \
src/FirmwarePlugin/FirmwarePluginManager.h \
src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/AutoPilotPlugins/AutoPilotPlugin.h \ src/AutoPilotPlugins/AutoPilotPlugin.h \
src/AutoPilotPlugins/AutoPilotPluginManager.h \ src/AutoPilotPlugins/AutoPilotPluginManager.h \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
...@@ -587,6 +582,12 @@ HEADERS+= \ ...@@ -587,6 +582,12 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/SafetyComponent.h \ src/AutoPilotPlugins/PX4/SafetyComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponent.h \ src/AutoPilotPlugins/PX4/SensorsComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponentController.h \ src/AutoPilotPlugins/PX4/SensorsComponentController.h \
src/FirmwarePlugin/FirmwarePluginManager.h \
src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/Vehicle/MultiVehicleManager.h \
src/Vehicle/Vehicle.h \
src/VehicleSetup/SetupView.h \ src/VehicleSetup/SetupView.h \
src/VehicleSetup/VehicleComponent.h \ src/VehicleSetup/VehicleComponent.h \
...@@ -600,9 +601,6 @@ HEADERS += \ ...@@ -600,9 +601,6 @@ HEADERS += \
} }
SOURCES += \ SOURCES += \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/AutoPilotPlugins/AutoPilotPlugin.cc \ src/AutoPilotPlugins/AutoPilotPlugin.cc \
src/AutoPilotPlugins/AutoPilotPluginManager.cc \ src/AutoPilotPlugins/AutoPilotPluginManager.cc \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \ src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
...@@ -622,6 +620,11 @@ SOURCES += \ ...@@ -622,6 +620,11 @@ SOURCES += \
src/AutoPilotPlugins/PX4/SafetyComponent.cc \ src/AutoPilotPlugins/PX4/SafetyComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/Vehicle.cc \
src/VehicleSetup/SetupView.cc \ src/VehicleSetup/SetupView.cc \
src/VehicleSetup/VehicleComponent.cc \ src/VehicleSetup/VehicleComponent.cc \
......
...@@ -30,16 +30,16 @@ ...@@ -30,16 +30,16 @@
#include "MainWindow.h" #include "MainWindow.h"
#include "ParameterLoader.h" #include "ParameterLoader.h"
AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) : AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
QObject(parent), QObject(parent),
_uas(uas), _vehicle(vehicle),
_pluginReady(false), _pluginReady(false),
_setupComplete(false) _setupComplete(false)
{ {
Q_ASSERT(_uas); Q_ASSERT(vehicle);
connect(_uas, &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected); connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(_uas, &UASInterface::armingChanged, this, &AutoPilotPlugin::armedChanged); connect(_vehicle->uas(), &UASInterface::armingChanged, this, &AutoPilotPlugin::armedChanged);
connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged); connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged);
} }
...@@ -102,8 +102,8 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void) ...@@ -102,8 +102,8 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
mavlink_message_t msg; mavlink_message_t msg;
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _uas->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 0, 2, -1, 0, 0, 0, 0, 0); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->uas()->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 0, 2, -1, 0, 0, 0, 0, 0);
_uas->sendMessage(msg); _vehicle->sendMessage(msg);
} }
void AutoPilotPlugin::refreshAllParameters(void) void AutoPilotPlugin::refreshAllParameters(void)
...@@ -169,7 +169,7 @@ const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void) ...@@ -169,7 +169,7 @@ const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{ {
_getParameterLoader()->writeParametersToStream(stream, _uas->getUASName()); _getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName());
} }
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
...@@ -179,5 +179,5 @@ QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) ...@@ -179,5 +179,5 @@ QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
bool AutoPilotPlugin::armed(void) bool AutoPilotPlugin::armed(void)
{ {
return _uas->isArmed(); return _vehicle->uas()->isArmed();
} }
...@@ -32,11 +32,12 @@ ...@@ -32,11 +32,12 @@
#include <QString> #include <QString>
#include <QQmlContext> #include <QQmlContext>
#include "UASInterface.h"
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "Vehicle.h"
class ParameterLoader; class ParameterLoader;
class Vehicle;
/// This is the base class for AutoPilot plugins /// This is the base class for AutoPilot plugins
/// ///
...@@ -50,7 +51,7 @@ class AutoPilotPlugin : public QObject ...@@ -50,7 +51,7 @@ class AutoPilotPlugin : public QObject
Q_OBJECT Q_OBJECT
public: public:
AutoPilotPlugin(UASInterface* uas, QObject* parent); AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin(); ~AutoPilotPlugin();
/// true: plugin is ready for use, plugin should no longer be used /// true: plugin is ready for use, plugin should no longer be used
...@@ -119,7 +120,7 @@ public: ...@@ -119,7 +120,7 @@ public:
bool setupComplete(void); bool setupComplete(void);
bool armed(void); bool armed(void);
UASInterface* uas(void) { return _uas; } Vehicle* vehicle(void) { return _vehicle; }
signals: signals:
void pluginReadyChanged(bool pluginReady); void pluginReadyChanged(bool pluginReady);
...@@ -134,9 +135,9 @@ protected: ...@@ -134,9 +135,9 @@ protected:
/// Returns the ParameterLoader /// Returns the ParameterLoader
virtual ParameterLoader* _getParameterLoader(void) = 0; virtual ParameterLoader* _getParameterLoader(void) = 0;
UASInterface* _uas; Vehicle* _vehicle;
bool _pluginReady; bool _pluginReady;
bool _setupComplete; bool _setupComplete;
private slots: private slots:
void _uasDisconnected(void); void _uasDisconnected(void);
......
...@@ -27,98 +27,26 @@ ...@@ -27,98 +27,26 @@
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "PX4/PX4AutoPilotPlugin.h" #include "PX4/PX4AutoPilotPlugin.h"
#include "Generic/GenericAutoPilotPlugin.h" #include "Generic/GenericAutoPilotPlugin.h"
#include "QGCApplication.h"
#include "QGCMessageBox.h"
#include "UASManager.h"
IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager)
AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) : AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) :
QGCSingleton(parent) QGCSingleton(parent)
{ {
UASManagerInterface* uasMgr = UASManager::instance();
Q_ASSERT(uasMgr);
// We need to track uas coming and going so that we can instantiate plugins for each uas
connect(uasMgr, &UASManagerInterface::UASCreated, this, &AutoPilotPluginManager::_uasCreated);
connect(uasMgr, SIGNAL(UASDeleted(UASInterface*)), this, SLOT(_uasDeleted(UASInterface*)));
} }
AutoPilotPluginManager::~AutoPilotPluginManager() AutoPilotPluginManager::~AutoPilotPluginManager()
{ {
#ifdef QT_DEBUG
foreach(MAV_AUTOPILOT mavType, _pluginMap.keys()) {
Q_ASSERT_X(_pluginMap[mavType].count() == 0, "AutoPilotPluginManager", "LinkManager::_shutdown should have already closed all uas");
}
#endif
_pluginMap.clear();
PX4AutoPilotPlugin::clearStaticData(); PX4AutoPilotPlugin::clearStaticData();
GenericAutoPilotPlugin::clearStaticData(); GenericAutoPilotPlugin::clearStaticData();
} }
/// Create the plugin for this uas AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle)
void AutoPilotPluginManager::_uasCreated(UASInterface* uas)
{
Q_ASSERT(uas);
MAV_AUTOPILOT autopilotType = static_cast<MAV_AUTOPILOT>(uas->getAutopilotType());
int uasId = uas->getUASID();
Q_ASSERT(uasId != 0);
if (_pluginMap.contains(autopilotType)) {
Q_ASSERT_X(!_pluginMap[autopilotType].contains(uasId), "AutoPilotPluginManager", "Either we have duplicate UAS ids, or a UAS was not removed correctly.");
}
AutoPilotPlugin* plugin;
switch (autopilotType) {
case MAV_AUTOPILOT_PX4:
plugin = new PX4AutoPilotPlugin(uas, this);
Q_CHECK_PTR(plugin);
_pluginMap[MAV_AUTOPILOT_PX4][uasId] = QSharedPointer<AutoPilotPlugin>(plugin);
break;
case MAV_AUTOPILOT_GENERIC:
default:
plugin = new GenericAutoPilotPlugin(uas, this);
Q_CHECK_PTR(plugin);
_pluginMap[MAV_AUTOPILOT_GENERIC][uasId] = QSharedPointer<AutoPilotPlugin>(plugin);
QGCMessageBox::warning("Partial Support AutoPilot",
"Warning: You have connected QGroundControl to a firmware flight stack which is only partially supported. "
"If you are using the APM Flight Stack it is currently recommended to use Mission Planner, APM Planner or Tower as your ground control station.");
}
}
/// Destroy the plugin associated with this uas
void AutoPilotPluginManager::_uasDeleted(UASInterface* uas)
{ {
Q_ASSERT(uas); if (vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
return new PX4AutoPilotPlugin(vehicle, vehicle);
MAV_AUTOPILOT autopilotType = _installedAutopilotType(static_cast<MAV_AUTOPILOT>(uas->getAutopilotType())); } else {
int uasId = uas->getUASID(); return new GenericAutoPilotPlugin(vehicle, vehicle);
Q_ASSERT(uasId != 0);
if (_pluginMap.contains(autopilotType) && _pluginMap[autopilotType].contains(uasId)) {
_pluginMap[autopilotType][uasId].clear();
_pluginMap[autopilotType].remove(uasId);
} }
} }
QSharedPointer<AutoPilotPlugin> AutoPilotPluginManager::getInstanceForAutoPilotPlugin(UASInterface* uas)
{
Q_ASSERT(uas);
MAV_AUTOPILOT autopilotType = _installedAutopilotType(static_cast<MAV_AUTOPILOT>(uas->getAutopilotType()));
int uasId = uas->getUASID();
Q_ASSERT(uasId != 0);
Q_ASSERT(_pluginMap.contains(autopilotType));
Q_ASSERT(_pluginMap[autopilotType].contains(uasId));
return _pluginMap[autopilotType][uasId];
}
/// If autopilot is not an installed plugin, returns MAV_AUTOPILOT_GENERIC
MAV_AUTOPILOT AutoPilotPluginManager::_installedAutopilotType(MAV_AUTOPILOT autopilot)
{
return _pluginMap.contains(autopilot) ? autopilot : MAV_AUTOPILOT_GENERIC;
}
...@@ -31,12 +31,9 @@ ...@@ -31,12 +31,9 @@
#include <QList> #include <QList>
#include <QString> #include <QString>
#include "UASInterface.h"
#include "VehicleComponent.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "QGCSingleton.h" #include "QGCSingleton.h"
#include "QGCMAVLink.h" #include "Vehicle.h"
/// AutoPilotPlugin manager is a singleton which maintains the list of AutoPilotPlugin objects. /// AutoPilotPlugin manager is a singleton which maintains the list of AutoPilotPlugin objects.
...@@ -47,23 +44,12 @@ class AutoPilotPluginManager : public QGCSingleton ...@@ -47,23 +44,12 @@ class AutoPilotPluginManager : public QGCSingleton
DECLARE_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) DECLARE_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager)
public: public:
/// Returns the singleton AutoPilotPlugin instance for the specified uas. Returned as QSharedPointer AutoPilotPlugin* newAutopilotPluginForVehicle(Vehicle* vehicle);
/// to prevent shutdown ordering problems with Qml destruction happening after Facts are destroyed.
/// @param uas Uas to get plugin for
QSharedPointer<AutoPilotPlugin> getInstanceForAutoPilotPlugin(UASInterface* uas);
private slots:
void _uasCreated(UASInterface* uas);
void _uasDeleted(UASInterface* uas);
private: private:
/// All access to singleton is through AutoPilotPluginManager::instance /// All access to singleton is through AutoPilotPluginManager::instance
AutoPilotPluginManager(QObject* parent = NULL); AutoPilotPluginManager(QObject* parent = NULL);
~AutoPilotPluginManager(); ~AutoPilotPluginManager();
MAV_AUTOPILOT _installedAutopilotType(MAV_AUTOPILOT autopilot);
QMap<MAV_AUTOPILOT, QMap<int, QSharedPointer<AutoPilotPlugin> > > _pluginMap; ///< Map of AutoPilot plugins _pluginMap[MAV_TYPE][UASid]
}; };
#endif #endif
...@@ -26,12 +26,12 @@ ...@@ -26,12 +26,12 @@
#include "GenericAutoPilotPlugin.h" #include "GenericAutoPilotPlugin.h"
GenericAutoPilotPlugin::GenericAutoPilotPlugin(UASInterface* uas, QObject* parent) : GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(uas, parent) AutoPilotPlugin(vehicle, parent)
{ {
Q_ASSERT(uas); Q_ASSERT(vehicle);
_parameterFacts = new GenericParameterFacts(this, uas, this); _parameterFacts = new GenericParameterFacts(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts); Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReady); connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReady);
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
#define GENERICAUTOPILOT_H #define GENERICAUTOPILOT_H
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "GenericParameterFacts.h" #include "GenericParameterFacts.h"
/// @file /// @file
...@@ -38,7 +37,7 @@ class GenericAutoPilotPlugin : public AutoPilotPlugin ...@@ -38,7 +37,7 @@ class GenericAutoPilotPlugin : public AutoPilotPlugin
Q_OBJECT Q_OBJECT
public: public:
GenericAutoPilotPlugin(UASInterface* uas, QObject* parent = NULL); GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent = NULL);
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
......
...@@ -28,8 +28,8 @@ ...@@ -28,8 +28,8 @@
#include <QDebug> #include <QDebug>
GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) : GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, uas, parent) ParameterLoader(autopilot, vehicle, parent)
{ {
Q_ASSERT(uas); Q_ASSERT(vehicle);
} }
...@@ -41,7 +41,7 @@ class GenericParameterFacts : public ParameterLoader ...@@ -41,7 +41,7 @@ class GenericParameterFacts : public ParameterLoader
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
GenericParameterFacts(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent = NULL); GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
/// Override from ParameterLoader /// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString(); } virtual QString getDefaultComponentIdParam(void) const { return QString(); }
......
...@@ -27,7 +27,7 @@ ...@@ -27,7 +27,7 @@
#include "AirframeComponentController.h" #include "AirframeComponentController.h"
#include "AirframeComponentAirframes.h" #include "AirframeComponentAirframes.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
...@@ -98,7 +98,7 @@ AirframeComponentController::~AirframeComponentController() ...@@ -98,7 +98,7 @@ AirframeComponentController::~AirframeComponentController()
void AirframeComponentController::changeAutostart(void) void AirframeComponentController::changeAutostart(void)
{ {
if (UASManager::instance()->getUASList().count() > 1) { if (MultiVehicleManager::instance()->vehicles().count() > 1) {
QGCMessageBox::warning("Airframe Config", "You cannot change airframe configuration while connected to multiple vehicles."); QGCMessageBox::warning("Airframe Config", "You cannot change airframe configuration while connected to multiple vehicles.");
return; return;
} }
......
...@@ -26,7 +26,6 @@ ...@@ -26,7 +26,6 @@
#include "FlightModesComponentController.h" #include "FlightModesComponentController.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include <QVariant> #include <QVariant>
......
...@@ -23,7 +23,6 @@ ...@@ -23,7 +23,6 @@
#include "PX4AutoPilotPlugin.h" #include "PX4AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "PX4ParameterLoader.h" #include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h" #include "PX4AirframeLoader.h"
#include "FlightModesComponentController.h" #include "FlightModesComponentController.h"
...@@ -64,8 +63,8 @@ union px4_custom_mode { ...@@ -64,8 +63,8 @@ union px4_custom_mode {
float data_float; float data_float;
}; };
PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) : PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(uas, parent), AutoPilotPlugin(vehicle, parent),
_parameterFacts(NULL), _parameterFacts(NULL),
_airframeComponent(NULL), _airframeComponent(NULL),
_radioComponent(NULL), _radioComponent(NULL),
...@@ -75,15 +74,15 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) : ...@@ -75,15 +74,15 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
_powerComponent(NULL), _powerComponent(NULL),
_incorrectParameterVersion(false) _incorrectParameterVersion(false)
{ {
Q_ASSERT(uas); Q_ASSERT(vehicle);
_parameterFacts = new PX4ParameterLoader(this, uas, this); _parameterFacts = new PX4ParameterLoader(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts); Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_pluginReadyPreChecks); connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_pluginReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress); connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress);
_airframeFacts = new PX4AirframeLoader(this, uas, this); _airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
Q_CHECK_PTR(_airframeFacts); Q_CHECK_PTR(_airframeFacts);
PX4ParameterLoader::loadParameterFactMetaData(); PX4ParameterLoader::loadParameterFactMetaData();
...@@ -105,7 +104,7 @@ void PX4AutoPilotPlugin::clearStaticData(void) ...@@ -105,7 +104,7 @@ void PX4AutoPilotPlugin::clearStaticData(void)
const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
{ {
if (_components.count() == 0 && !_incorrectParameterVersion) { if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_uas); Q_ASSERT(_vehicle);
if (pluginReady()) { if (pluginReady()) {
bool noRCTransmitter = false; bool noRCTransmitter = false;
...@@ -114,34 +113,34 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) ...@@ -114,34 +113,34 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
noRCTransmitter = rcFact->value().toInt() == 1; noRCTransmitter = rcFact->value().toInt() == 1;
} }
_airframeComponent = new AirframeComponent(_uas, this); _airframeComponent = new AirframeComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_airframeComponent); Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals(); _airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
if (!noRCTransmitter) { if (!noRCTransmitter) {
_radioComponent = new RadioComponent(_uas, this); _radioComponent = new RadioComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_radioComponent); Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals(); _radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
_flightModesComponent = new FlightModesComponent(_uas, this); _flightModesComponent = new FlightModesComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_flightModesComponent); Q_CHECK_PTR(_flightModesComponent);
_flightModesComponent->setupTriggerSignals(); _flightModesComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
} }
_sensorsComponent = new SensorsComponent(_uas, this); _sensorsComponent = new SensorsComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_sensorsComponent); Q_CHECK_PTR(_sensorsComponent);
_sensorsComponent->setupTriggerSignals(); _sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
_powerComponent = new PowerComponent(_uas, this); _powerComponent = new PowerComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_powerComponent); Q_CHECK_PTR(_powerComponent);
_powerComponent->setupTriggerSignals(); _powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
_safetyComponent = new SafetyComponent(_uas, this); _safetyComponent = new SafetyComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_safetyComponent); Q_CHECK_PTR(_safetyComponent);
_safetyComponent->setupTriggerSignals(); _safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
......
...@@ -25,8 +25,6 @@ ...@@ -25,8 +25,6 @@
#define PX4AUTOPILOT_H #define PX4AUTOPILOT_H
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "UASInterface.h"
#include "PX4ParameterLoader.h" #include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h" #include "PX4AirframeLoader.h"
#include "AirframeComponent.h" #include "AirframeComponent.h"
...@@ -35,6 +33,7 @@ ...@@ -35,6 +33,7 @@
#include "SensorsComponent.h" #include "SensorsComponent.h"
#include "SafetyComponent.h" #include "SafetyComponent.h"
#include "PowerComponent.h" #include "PowerComponent.h"
#include "Vehicle.h"
#include <QImage> #include <QImage>
...@@ -47,7 +46,7 @@ class PX4AutoPilotPlugin : public AutoPilotPlugin ...@@ -47,7 +46,7 @@ class PX4AutoPilotPlugin : public AutoPilotPlugin
Q_OBJECT Q_OBJECT
public: public:
PX4AutoPilotPlugin(UASInterface* uas, QObject* parent); PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~PX4AutoPilotPlugin(); ~PX4AutoPilotPlugin();
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
......
...@@ -38,10 +38,10 @@ QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog") ...@@ -38,10 +38,10 @@ QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog")
bool PX4ParameterLoader::_parameterMetaDataLoaded = false; bool PX4ParameterLoader::_parameterMetaDataLoaded = false;
QMap<QString, FactMetaData*> PX4ParameterLoader::_mapParameterName2FactMetaData; QMap<QString, FactMetaData*> PX4ParameterLoader::_mapParameterName2FactMetaData;
PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) : PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, uas, parent) ParameterLoader(autopilot, vehicle, parent)
{ {
Q_ASSERT(uas); Q_ASSERT(vehicle);
} }
/// Converts a string to a typed QVariant /// Converts a string to a typed QVariant
......
...@@ -31,8 +31,8 @@ ...@@ -31,8 +31,8 @@
#include "ParameterLoader.h" #include "ParameterLoader.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "Vehicle.h"
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
...@@ -47,7 +47,7 @@ class PX4ParameterLoader : public ParameterLoader ...@@ -47,7 +47,7 @@ class PX4ParameterLoader : public ParameterLoader
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
PX4ParameterLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL); PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
/// Override from ParameterLoader /// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
......
...@@ -26,7 +26,6 @@ ...@@ -26,7 +26,6 @@
#include "PowerComponentController.h" #include "PowerComponentController.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "UASManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include <QVariant> #include <QVariant>
...@@ -71,7 +70,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int ...@@ -71,7 +70,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int
Q_UNUSED(compId); Q_UNUSED(compId);
Q_UNUSED(severity); Q_UNUSED(severity);
UASInterface* uas = _autopilot->uas(); UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas); Q_ASSERT(uas);
if (uasId != uas->getUASID()) { if (uasId != uas->getUASID()) {
return; return;
......
...@@ -26,7 +26,6 @@ ...@@ -26,7 +26,6 @@
/// @author Don Gagne <don@thegagnes.com /// @author Don Gagne <don@thegagnes.com
#include "RadioComponentController.h" #include "RadioComponentController.h"
#include "UASManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
......
...@@ -26,7 +26,6 @@ ...@@ -26,7 +26,6 @@
#include "SensorsComponentController.h" #include "SensorsComponentController.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "UASManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include <QVariant> #include <QVariant>
...@@ -208,7 +207,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in ...@@ -208,7 +207,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
Q_UNUSED(compId); Q_UNUSED(compId);
Q_UNUSED(severity); Q_UNUSED(severity);
UASInterface* uas = _autopilot->uas(); UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas); Q_ASSERT(uas);
if (uasId != uas->getUASID()) { if (uasId != uas->getUASID()) {
return; return;
...@@ -427,7 +426,7 @@ void SensorsComponentController::_refreshParams(void) ...@@ -427,7 +426,7 @@ void SensorsComponentController::_refreshParams(void)
bool SensorsComponentController::fixedWing(void) bool SensorsComponentController::fixedWing(void)
{ {
UASInterface* uas = _autopilot->uas(); UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas); Q_ASSERT(uas);
return uas->getSystemType() == MAV_TYPE_FIXED_WING || return uas->getSystemType() == MAV_TYPE_FIXED_WING ||
uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR || uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
......
...@@ -22,8 +22,7 @@ ...@@ -22,8 +22,7 @@
======================================================================*/ ======================================================================*/
#include "FactPanelController.h" #include "FactPanelController.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include <QQmlEngine> #include <QQmlEngine>
...@@ -34,15 +33,15 @@ ...@@ -34,15 +33,15 @@
QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog") QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog")
FactPanelController::FactPanelController(void) : FactPanelController::FactPanelController(void) :
_autopilot(NULL),
_factPanel(NULL) _factPanel(NULL)
{ {
// FIXME: Get rid of these asserts _vehicle = MultiVehicleManager::instance()->activeVehicle();
Q_ASSERT(_vehicle);
_uas = UASManager::instance()->getActiveUAS(); _uas = _vehicle->uas();
Q_ASSERT(_uas); Q_ASSERT(_uas);
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas); _autopilot = _vehicle->autopilotPlugin();
Q_ASSERT(_autopilot); Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->pluginReady()); Q_ASSERT(_autopilot->pluginReady());
......
...@@ -32,7 +32,6 @@ ...@@ -32,7 +32,6 @@
#include "UASInterface.h" #include "UASInterface.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "UASManagerInterface.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(FactPanelControllerLog) Q_DECLARE_LOGGING_CATEGORY(FactPanelControllerLog)
...@@ -62,8 +61,9 @@ protected: ...@@ -62,8 +61,9 @@ protected:
/// Report a missing parameter to the FactPanel Qml element /// Report a missing parameter to the FactPanel Qml element
void _reportMissingParameter(int componentId, const QString& name); void _reportMissingParameter(int componentId, const QString& name);
UASInterface* _uas; Vehicle* _vehicle;
QSharedPointer<AutoPilotPlugin> _autopilot; UASInterface* _uas;
AutoPilotPlugin* _autopilot;
private slots: private slots:
void _checkForMissingFactPanel(void); void _checkForMissingFactPanel(void);
......
...@@ -25,8 +25,6 @@ ...@@ -25,8 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FactSystem.h" #include "FactSystem.h"
#include "UASManager.h"
#include "QGCApplication.h"
#include "FactPanelController.h" #include "FactPanelController.h"
#include <QtQml> #include <QtQml>
......
...@@ -27,8 +27,7 @@ ...@@ -27,8 +27,7 @@
#include "FactSystemTestBase.h" #include "FactSystemTestBase.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "MockLink.h" #include "MockLink.h"
#include "AutoPilotPluginManager.h" #include "MultiVehicleManager.h"
#include "UASManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "QGCQuickWidget.h" #include "QGCQuickWidget.h"
...@@ -45,45 +44,20 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot) ...@@ -45,45 +44,20 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
{ {
UnitTest::init(); UnitTest::init();
LinkManager* _linkMgr = LinkManager::instance();
MockLink* link = new MockLink(); MockLink* link = new MockLink();
link->setAutopilotType(autopilot); link->setAutopilotType(autopilot);
_linkMgr->_addLink(link); LinkManager::instance()->_addLink(link);
if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Connect will pop a warning dialog
setExpectedMessageBox(QGCMessageBox::Ok);
}
_linkMgr->connectLink(link);
// Wait for the uas to work it's way through the various threads
QSignalSpy spyUas(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)));
QCOMPARE(spyUas.wait(5000), true);
if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) { LinkManager::instance()->connectLink(link);
checkExpectedMessageBox();
}
_uas = UASManager::instance()->getActiveUAS(); // Wait for the Vehicle to get created
Q_ASSERT(_uas); QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QCOMPARE(spyVehicle.wait(5000), true);
QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable());
QVERIFY(MultiVehicleManager::instance()->activeVehicle());
// Get the plugin for the uas _plugin = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin();
AutoPilotPluginManager* pluginMgr = AutoPilotPluginManager::instance();
Q_ASSERT(pluginMgr);
_plugin = pluginMgr->getInstanceForAutoPilotPlugin(_uas).data();
Q_ASSERT(_plugin); Q_ASSERT(_plugin);
// Wait for the plugin to be ready
QSignalSpy spyPlugin(_plugin, SIGNAL(pluginReadyChanged(bool)));
if (!_plugin->pluginReady()) {
QCOMPARE(spyPlugin.wait(60000), true);
}
Q_ASSERT(_plugin->pluginReady());
} }
void FactSystemTestBase::_cleanup(void) void FactSystemTestBase::_cleanup(void)
......
...@@ -48,9 +48,7 @@ protected: ...@@ -48,9 +48,7 @@ protected:
void _qml_test(void); void _qml_test(void);
void _qmlUpdate_test(void); void _qmlUpdate_test(void);
UASInterface* _uas;
AutoPilotPlugin* _plugin; AutoPilotPlugin* _plugin;
LinkManager* _linkMgr;
}; };
#endif #endif
...@@ -25,14 +25,7 @@ ...@@ -25,14 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FactSystemTestGeneric.h" #include "FactSystemTestGeneric.h"
#include "LinkManager.h" #include "QGCMAVLink.h"
#include "MockLink.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "QGCApplication.h"
#include "QGCQuickWidget.h"
#include <QQuickItem>
UT_REGISTER_TEST(FactSystemTestGeneric) UT_REGISTER_TEST(FactSystemTestGeneric)
......
...@@ -25,14 +25,7 @@ ...@@ -25,14 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FactSystemTestPX4.h" #include "FactSystemTestPX4.h"
#include "LinkManager.h" #include "QGCMAVLink.h"
#include "MockLink.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "QGCApplication.h"
#include "QGCQuickWidget.h"
#include <QQuickItem>
UT_REGISTER_TEST(FactSystemTestPX4) UT_REGISTER_TEST(FactSystemTestPX4)
......
...@@ -38,10 +38,10 @@ QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog") ...@@ -38,10 +38,10 @@ QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
Fact ParameterLoader::_defaultFact; Fact ParameterLoader::_defaultFact;
ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) : ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
QObject(parent), QObject(parent),
_autopilot(autopilot), _autopilot(autopilot),
_uas(uas), _vehicle(vehicle),
_mavlink(MAVLinkProtocol::instance()), _mavlink(MAVLinkProtocol::instance()),
_parametersReady(false), _parametersReady(false),
_initialLoadComplete(false), _initialLoadComplete(false),
...@@ -49,7 +49,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, ...@@ -49,7 +49,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas,
_totalParamCount(0) _totalParamCount(0)
{ {
Q_ASSERT(_autopilot); Q_ASSERT(_autopilot);
Q_ASSERT(_uas); Q_ASSERT(_vehicle);
Q_ASSERT(_mavlink); Q_ASSERT(_mavlink);
// We signal this to ouselves in order to start timer on our thread // We signal this to ouselves in order to start timer on our thread
...@@ -60,7 +60,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, ...@@ -60,7 +60,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas,
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout); connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
// FIXME: Why not direct connect? // FIXME: Why not direct connect?
connect(_uas, SIGNAL(parameterUpdate(int, int, QString, int, int, int, QVariant)), this, SLOT(_parameterUpdate(int, int, QString, int, int, int, QVariant))); connect(_vehicle->uas(), SIGNAL(parameterUpdate(int, int, QString, int, int, int, QVariant)), this, SLOT(_parameterUpdate(int, int, QString, int, int, int, QVariant)));
// Request full param list // Request full param list
refreshAllParameters(); refreshAllParameters();
...@@ -77,7 +77,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param ...@@ -77,7 +77,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
bool setMetaData = false; bool setMetaData = false;
// Is this for our uas? // Is this for our uas?
if (uasId != _uas->getUASID()) { if (uasId != _vehicle->id()) {
return; return;
} }
...@@ -297,8 +297,8 @@ void ParameterLoader::refreshAllParameters(void) ...@@ -297,8 +297,8 @@ void ParameterLoader::refreshAllParameters(void)
Q_ASSERT(mavlink); Q_ASSERT(mavlink);
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _uas->getUASID(), MAV_COMP_ID_ALL); mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL);
_uas->sendMessage(msg); _vehicle->sendMessage(msg);
qCDebug(ParameterLoaderLog) << "Request to refresh all parameters"; qCDebug(ParameterLoaderLog) << "Request to refresh all parameters";
} }
...@@ -490,16 +490,16 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam ...@@ -490,16 +490,16 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam
mavlink_msg_param_request_read_pack(_mavlink->getSystemId(), // Our system id mavlink_msg_param_request_read_pack(_mavlink->getSystemId(), // Our system id
_mavlink->getComponentId(), // Our component id _mavlink->getComponentId(), // Our component id
&msg, // Pack into this mavlink_message_t &msg, // Pack into this mavlink_message_t
_uas->getUASID(), // Target system id _vehicle->id(), // Target system id
componentId, // Target component id componentId, // Target component id
fixedParamName, // Named parameter being requested fixedParamName, // Named parameter being requested
paramIndex); // Parameter index being requested, -1 for named paramIndex); // Parameter index being requested, -1 for named
_uas->sendMessage(msg); _vehicle->sendMessage(msg);
} }
void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value) void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{ {
bool floatHack = _uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA; bool floatHack = _vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA;
mavlink_param_set_t p; mavlink_param_set_t p;
mavlink_param_union_t union_value; mavlink_param_union_t union_value;
...@@ -566,21 +566,21 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa ...@@ -566,21 +566,21 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa
} }
p.param_value = union_value.param_float; p.param_value = union_value.param_float;
p.target_system = (uint8_t)_uas->getUASID(); p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)componentId; p.target_component = (uint8_t)componentId;
strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id)); strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p); mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
_uas->sendMessage(msg); _vehicle->sendMessage(msg);
} }
void ParameterLoader::_saveToEEPROM(void) void ParameterLoader::_saveToEEPROM(void)
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _uas->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
_uas->sendMessage(msg); _vehicle->sendMessage(msg);
qCDebug(ParameterLoaderLog) << "_saveToEEPROM"; qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
} }
...@@ -595,11 +595,11 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream) ...@@ -595,11 +595,11 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QStringList wpParams = line.split("\t"); QStringList wpParams = line.split("\t");
int lineMavId = wpParams.at(0).toInt(); int lineMavId = wpParams.at(0).toInt();
if (wpParams.size() == 5) { if (wpParams.size() == 5) {
if (!userWarned && (_uas->getUASID() != lineMavId)) { if (!userWarned && (_vehicle->id() != lineMavId)) {
userWarned = true; userWarned = true;
QString msg("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2."); QString msg("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.");
QGCMessageBox::StandardButton button = QGCMessageBox::warning("Parameter Load", QGCMessageBox::StandardButton button = QGCMessageBox::warning("Parameter Load",
msg.arg(lineMavId).arg(_uas->getUASID()), msg.arg(lineMavId).arg(_vehicle->id()),
QGCMessageBox::Ok | QGCMessageBox::Cancel, QGCMessageBox::Ok | QGCMessageBox::Cancel,
QGCMessageBox::Cancel); QGCMessageBox::Cancel);
if (button == QGCMessageBox::Cancel) { if (button == QGCMessageBox::Cancel) {
...@@ -649,7 +649,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream, const QString ...@@ -649,7 +649,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream, const QString
Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>(); Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
Q_ASSERT(fact); Q_ASSERT(fact);
stream << _uas->getUASID() << "\t" << componentId << "\t" << paramName << "\t" << fact->valueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n"; stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->valueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
} }
} }
......
...@@ -31,10 +31,10 @@ ...@@ -31,10 +31,10 @@
#include <QMutex> #include <QMutex>
#include "FactSystem.h" #include "FactSystem.h"
#include "UASInterface.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "Vehicle.h"
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
...@@ -48,7 +48,7 @@ class ParameterLoader : public QObject ...@@ -48,7 +48,7 @@ class ParameterLoader : public QObject
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent = NULL); ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
~ParameterLoader(); ~ParameterLoader();
...@@ -123,7 +123,7 @@ private: ...@@ -123,7 +123,7 @@ private:
void _checkInitialLoadComplete(void); void _checkInitialLoadComplete(void);
AutoPilotPlugin* _autopilot; AutoPilotPlugin* _autopilot;
UASInterface* _uas; Vehicle* _vehicle;
MAVLinkProtocol* _mavlink; MAVLinkProtocol* _mavlink;
/// First mapping is by component id /// First mapping is by component id
......
...@@ -86,8 +86,10 @@ G_END_DECLS ...@@ -86,8 +86,10 @@ G_END_DECLS
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "MavManager.h" #include "MavManager.h"
#include "FirmwarePluginManager.h" #include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h"
#include "Generic/GenericFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h"
#include "PX4/PX4FirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h"
#include "Vehicle.h"
#ifdef QGC_RTLAB_ENABLED #ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h" #include "OpalLink.h"
...@@ -339,6 +341,7 @@ void QGCApplication::_initCommon(void) ...@@ -339,6 +341,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<AutoPilotPlugin>("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Can only reference, cannot create"); qmlRegisterUncreatableType<AutoPilotPlugin>("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Can only reference, cannot create");
qmlRegisterUncreatableType<VehicleComponent>("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create"); qmlRegisterUncreatableType<VehicleComponent>("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create");
qmlRegisterUncreatableType<Vehicle>("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create");
qmlRegisterType<ViewWidgetController>("QGroundControl.Controllers", 1, 0, "ViewWidgetController"); qmlRegisterType<ViewWidgetController>("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<ParameterEditorController>("QGroundControl.Controllers", 1, 0, "ParameterEditorController"); qmlRegisterType<ParameterEditorController>("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
...@@ -379,9 +382,6 @@ void QGCApplication::_initCommon(void) ...@@ -379,9 +382,6 @@ void QGCApplication::_initCommon(void)
"Your saved settings have been reset to defaults.")); "Your saved settings have been reset to defaults."));
} }
_styleIsDark = settings.value(_styleKey, _styleIsDark).toBool();
_loadCurrentStyle();
// Load saved files location and validate // Load saved files location and validate
QString savedFilesLocation; QString savedFilesLocation;
...@@ -421,6 +421,9 @@ bool QGCApplication::_initForNormalAppBoot(void) ...@@ -421,6 +421,9 @@ bool QGCApplication::_initForNormalAppBoot(void)
_createSingletons(); _createSingletons();
_styleIsDark = settings.value(_styleKey, _styleIsDark).toBool();
_loadCurrentStyle();
// Show splash screen // Show splash screen
QPixmap splashImage(":/res/SplashScreen"); QPixmap splashImage(":/res/SplashScreen");
QSplashScreen* splashScreen = new QSplashScreen(splashImage); QSplashScreen* splashScreen = new QSplashScreen(splashImage);
...@@ -583,6 +586,11 @@ void QGCApplication::_createSingletons(void) ...@@ -583,6 +586,11 @@ void QGCApplication::_createSingletons(void)
Q_UNUSED(firmwarePluginManager); Q_UNUSED(firmwarePluginManager);
Q_ASSERT(firmwarePluginManager); Q_ASSERT(firmwarePluginManager);
// No dependencies
MultiVehicleManager* multiVehicleManager = MultiVehicleManager::_createSingleton();
Q_UNUSED(multiVehicleManager);
Q_ASSERT(multiVehicleManager);
// No dependencies // No dependencies
GAudioOutput* audio = GAudioOutput::_createSingleton(); GAudioOutput* audio = GAudioOutput::_createSingleton();
Q_UNUSED(audio); Q_UNUSED(audio);
...@@ -631,11 +639,6 @@ void QGCApplication::_destroySingletons(void) ...@@ -631,11 +639,6 @@ void QGCApplication::_destroySingletons(void)
LinkManager::instance()->_shutdown(); LinkManager::instance()->_shutdown();
} }
if (UASManager::instance(true /* nullOk */)) {
// This will delete all uas from the system
UASManager::instance()->_shutdown();
}
// Let the signals flow through the main thread // Let the signals flow through the main thread
processEvents(QEventLoop::ExcludeUserInputEvents); processEvents(QEventLoop::ExcludeUserInputEvents);
...@@ -648,6 +651,7 @@ void QGCApplication::_destroySingletons(void) ...@@ -648,6 +651,7 @@ void QGCApplication::_destroySingletons(void)
UASManager::_deleteSingleton(); UASManager::_deleteSingleton();
LinkManager::_deleteSingleton(); LinkManager::_deleteSingleton();
GAudioOutput::_deleteSingleton(); GAudioOutput::_deleteSingleton();
MultiVehicleManager::_deleteSingleton();
FirmwarePluginManager::_deleteSingleton(); FirmwarePluginManager::_deleteSingleton();
GenericFirmwarePlugin::_deleteSingleton(); GenericFirmwarePlugin::_deleteSingleton();
PX4FirmwarePlugin::_deleteSingleton(); PX4FirmwarePlugin::_deleteSingleton();
......
...@@ -24,6 +24,7 @@ ...@@ -24,6 +24,7 @@
#include "QGCQuickWidget.h" #include "QGCQuickWidget.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "MultiVehicleManager.h"
#include <QQmlContext> #include <QQmlContext>
#include <QQmlEngine> #include <QQmlEngine>
...@@ -38,6 +39,7 @@ QGCQuickWidget::QGCQuickWidget(QWidget* parent) : ...@@ -38,6 +39,7 @@ QGCQuickWidget::QGCQuickWidget(QWidget* parent) :
QQuickWidget(parent) QQuickWidget(parent)
{ {
rootContext()->engine()->addImportPath("qrc:/qml"); rootContext()->engine()->addImportPath("qrc:/qml");
rootContext()->setContextProperty("multiVehicleManager", MultiVehicleManager::instance());
} }
void QGCQuickWidget::setAutoPilot(AutoPilotPlugin* autoPilot) void QGCQuickWidget::setAutoPilot(AutoPilotPlugin* autoPilot)
......
...@@ -29,7 +29,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -29,7 +29,7 @@ This file is part of the QGROUNDCONTROL project
#include "UAS.h" #include "UAS.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "Waypoint.h" #include "Waypoint.h"
#include "MavManager.h" #include "MavManager.h"
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
...@@ -76,9 +76,9 @@ MavManager::MavManager(QObject *parent) ...@@ -76,9 +76,9 @@ MavManager::MavManager(QObject *parent)
, _updateCount(0) , _updateCount(0)
{ {
// Connect with UAS signal // Connect with UAS signal
_setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
connect(UASManager::instance(), SIGNAL(UASDeleted(UASInterface*)), this, SLOT(_forgetUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MavManager::_activeVehicleChanged);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(_setActiveUAS(UASInterface*)));
// Refresh timer // Refresh timer
connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate()));
_refreshTimer->setInterval(UPDATE_TIMER); _refreshTimer->setInterval(UPDATE_TIMER);
...@@ -103,9 +103,10 @@ QString MavManager::loadSetting(const QString &name, const QString& defaultValue ...@@ -103,9 +103,10 @@ QString MavManager::loadSetting(const QString &name, const QString& defaultValue
return settings.value(name, defaultValue).toString(); return settings.value(name, defaultValue).toString();
} }
void MavManager::_forgetUAS(UASInterface* uas) void MavManager::_activeVehicleChanged(Vehicle* vehicle)
{ {
if (_mav != NULL && _mav == uas) { // Disconnect the previous one (if any)
if (_mav) {
// Stop listening for system messages // Stop listening for system messages
disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage); disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage);
// Disconnect any previously connected active MAV // Disconnect any previously connected active MAV
...@@ -139,25 +140,17 @@ void MavManager::_forgetUAS(UASInterface* uas) ...@@ -139,25 +140,17 @@ void MavManager::_forgetUAS(UASInterface* uas)
emit mavPresentChanged(); emit mavPresentChanged();
emit satelliteCountChanged(); emit satelliteCountChanged();
} }
}
_mav = NULL;
void MavManager::_setActiveUAS(UASInterface* uas)
{ if (vehicle) {
if (uas == _mav) _mav = vehicle->uas();
return;
// Disconnect the previous one (if any)
if(_mav) {
_forgetUAS(_mav);
}
if (uas) {
// Reset satellite count (no GPS) // Reset satellite count (no GPS)
_satelliteCount = -1; _satelliteCount = -1;
emit satelliteCountChanged(); emit satelliteCountChanged();
// Reset connection lost (if any) // Reset connection lost (if any)
_currentHeartbeatTimeout = 0; _currentHeartbeatTimeout = 0;
emit heartbeatTimeoutChanged(); emit heartbeatTimeoutChanged();
// Set new UAS
_mav = uas;
// Listen for system messages // Listen for system messages
connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage); connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage);
// Now connect the new UAS // Now connect the new UAS
......
...@@ -33,7 +33,9 @@ This file is part of the QGROUNDCONTROL project ...@@ -33,7 +33,9 @@ This file is part of the QGROUNDCONTROL project
#include <QObject> #include <QObject>
#include <QTimer> #include <QTimer>
#include <QQmlListProperty> #include <QQmlListProperty>
#include "Waypoint.h" #include "Waypoint.h"
#include "Vehicle.h"
class UASInterface; class UASInterface;
class UASWaypointManager; class UASWaypointManager;
...@@ -172,6 +174,7 @@ signals: ...@@ -172,6 +174,7 @@ signals:
void waypointsChanged (); void waypointsChanged ();
private slots: private slots:
void _activeVehicleChanged(Vehicle* vehicle);
void _handleTextMessage (int newCount); void _handleTextMessage (int newCount);
/** @brief Attitude from main autopilot / system state */ /** @brief Attitude from main autopilot / system state */
void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
...@@ -183,8 +186,6 @@ private slots: ...@@ -183,8 +186,6 @@ private slots:
void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp); void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp);
void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError); void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError);
void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance); void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance);
void _forgetUAS (UASInterface* uas);
void _setActiveUAS (UASInterface* uas);
void _checkUpdate (); void _checkUpdate ();
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int);
void _updateBatteryConsumedChanged (UASInterface*, double current_consumed); void _updateBatteryConsumedChanged (UASInterface*, double current_consumed);
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "ParameterEditorController.h" #include "ParameterEditorController.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
......
/*=====================================================================
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/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "MultiVehicleManager.h"
#include "AutoPilotPlugin.h"
IMPLEMENT_QGC_SINGLETON(MultiVehicleManager, MultiVehicleManager)
MultiVehicleManager::MultiVehicleManager(QObject* parent) :
QGCSingleton(parent)
, _activeVehicleAvailable(false)
, _parameterReadyVehicleAvailable(false)
, _activeVehicle(NULL)
, _offlineWaypointManager(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<MultiVehicleManager>("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only");
}
MultiVehicleManager::~MultiVehicleManager()
{
}
bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat)
{
if (!_vehicleMap.contains(vehicleId) && !_ignoreVehicleIds.contains(vehicleId)) {
if (vehicleId == MAVLinkProtocol::instance()->getSystemId()) {
qgcApp()->showToolBarMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId));
}
QSettings settings;
bool mavlinkVersionCheck = settings.value("VERSION_CHECK_ENABLED", true).toBool();
if (mavlinkVersionCheck && heartbeat.mavlink_version != MAVLINK_VERSION) {
_ignoreVehicleIds += vehicleId;
qgcApp()->showToolBarMessage(QString("The MAVLink protocol version on vehicle #%1 and QGroundControl differ! "
"It is unsafe to use different MAVLink versions. "
"QGroundControl therefore refuses to connect to vehicle #%1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(vehicleId).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
return false;
}
Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)heartbeat.autopilot);
if (!vehicle) {
qWarning() << "New Vehicle allocation failed";
return false;
}
connect(vehicle, &Vehicle::allLinksDisconnected, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::pluginReadyChanged, this, &MultiVehicleManager::_autopilotPluginReadyChanged);
_vehicleMap[vehicleId] = vehicle;
emit vehicleAdded(vehicle);
setActiveVehicle(vehicle);
}
return true;
}
/// This slot is connected to the Vehicle::allLinksDestroyed signal such that the Vehicle is deleted
/// and all other right things happen when the Vehicle goes away.
void MultiVehicleManager::_deleteVehiclePhase1(void)
{
Vehicle* vehicle = dynamic_cast<Vehicle*>(sender());
if (!vehicle) {
qWarning() << "Dynamic cast failed!";
return;
}
_vehicleBeingDeleted = vehicle;
// Remove from map
bool found;
foreach(int id, _vehicleMap.keys()) {
if (_vehicleMap[id] == _vehicleBeingDeleted) {
_vehicleMap.remove(id);
found = true;
break;
}
}
if (!found) {
qWarning() << "Vehicle not found in map!";
}
// First we must signal that a vehicle is no longer available.
_activeVehicleAvailable = false;
_parameterReadyVehicleAvailable = false;
emit activeVehicleAvailableChanged(false);
emit parameterReadyVehicleAvailableChanged(false);
emit vehicleRemoved(vehicle);
// We must let the above signals flow through the system as well as get back to the main loop event queue
// before we can actually delete the Vehicle. The reason is that Qml may be holding on the references to it.
// Even though the above signals should unload any Qml which has references, that Qml will not be destroyed
// until we get back to the main loop. So we set a short timer which will then fire after Qt has finished
// doing all of its internal nastiness to clean up the Qml. This works for both the normal running case
// as well as the unit testing case whichof course has a different signal flow!
QTimer::singleShot(20, this, &MultiVehicleManager::_deleteVehiclePhase2);
}
void MultiVehicleManager::_deleteVehiclePhase2 (void)
{
/// Qml has been notified of vehicle about to go away and should be disconnected from it by now.
/// This means we can now clear the active vehicle property and delete the Vehicle for real.
Vehicle* newActiveVehicle = NULL;
if (_vehicleMap.count()) {
newActiveVehicle = _vehicleMap.first();
}
_activeVehicle = newActiveVehicle;
emit activeVehicleChanged(newActiveVehicle);
if (_activeVehicle) {
emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->pluginReady()) {
emit parameterReadyVehicleAvailableChanged(true);
}
}
_vehicleBeingDeleted->deleteLater();
}
void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle)
{
if (vehicle != _activeVehicle) {
if (_activeVehicle) {
// The sequence of signals is very important in order to not leave Qml elements connected
// to a non-existent vehicle.
// First we must signal that there is no active vehicle available. This will disconnect
// any existing ui from the currently active vehicle.
_activeVehicleAvailable = false;
_parameterReadyVehicleAvailable = false;
emit activeVehicleAvailableChanged(false);
emit parameterReadyVehicleAvailableChanged(false);
}
// See explanation in _deleteVehiclePhase1
_vehicleBeingSetActive = vehicle;
QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
}
}
void MultiVehicleManager::_setActiveVehiclePhase2(void)
{
// Now we signal the new active vehicle
_activeVehicle = _vehicleBeingSetActive;
emit activeVehicleChanged(_activeVehicle);
// And finally vehicle availability
if (_activeVehicle) {
_activeVehicleAvailable = true;
emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->pluginReady()) {
_parameterReadyVehicleAvailable = true;
emit parameterReadyVehicleAvailableChanged(true);
}
}
}
void MultiVehicleManager::_autopilotPluginReadyChanged(bool pluginReady)
{
AutoPilotPlugin* autopilot = dynamic_cast<AutoPilotPlugin*>(sender());
if (!autopilot) {
qWarning() << "Dynamic cast failed!";
return;
}
if (autopilot->vehicle() == _activeVehicle) {
_parameterReadyVehicleAvailable = pluginReady;
emit parameterReadyVehicleAvailableChanged(pluginReady);
}
}
void MultiVehicleManager::setHomePositionForAllVehicles(double lat, double lon, double alt)
{
foreach (Vehicle* vehicle, _vehicleMap) {
vehicle->uas()->setHomePosition(lat, lon, alt);
}
}
UASWaypointManager* MultiVehicleManager::activeWaypointManager(void)
{
if (_activeVehicle) {
return _activeVehicle->uas()->getWaypointManager();
}
if (!_offlineWaypointManager) {
_offlineWaypointManager = new UASWaypointManager(NULL, NULL);
}
return _offlineWaypointManager;
}
QList<Vehicle*> MultiVehicleManager::vehicles(void)
{
QList<Vehicle*> list;
foreach (Vehicle* vehicle, _vehicleMap) {
list += vehicle;
}
return list;
}
/*=====================================================================
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/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef MultiVehicleManager_H
#define MultiVehicleManager_H
#include "QGCSingleton.h"
#include "Vehicle.h"
#include "QGCMAVLink.h"
#include "UASWaypointManager.h"
class MultiVehicleManager : public QGCSingleton
{
Q_OBJECT
DECLARE_QGC_SINGLETON(MultiVehicleManager, MultiVehicleManager)
public:
Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged)
Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
// Property accessors
bool activeVehicleAvailable(void) { return _activeVehicleAvailable; }
bool parameterReadyVehicleAvailable(void) { return _parameterReadyVehicleAvailable; }
Vehicle* activeVehicle(void) { return _activeVehicle; }
void setActiveVehicle(Vehicle* vehicle);
/// Called to notify that a heartbeat was received with the specified information. MultiVehicleManager
/// will create/update Vehicles as necessary.
/// @param link Heartbeat came through on this link
/// @param vehicleId Mavlink system id for vehicle
/// @param heartbeat Mavlink heartbeat message
/// @return true: continue further processing of this message, false: disregard this message
bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat);
Vehicle* getVehicleById(int vehicleId) { return _vehicleMap[vehicleId]; }
void setHomePositionForAllVehicles(double lat, double lon, double alt);
UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : NULL; }
QList<Vehicle*> vehicles(void);
UASWaypointManager* activeWaypointManager(void);
signals:
void vehicleAdded(Vehicle* vehicle);
void vehicleRemoved(Vehicle* vehicle);
void activeVehicleAvailableChanged(bool activeVehicleAvailable);
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable);
void activeVehicleChanged(Vehicle* activeVehicle);
void _deleteVehiclePhase2Signal(void);
private slots:
void _deleteVehiclePhase1(void);
void _deleteVehiclePhase2(void);
void _setActiveVehiclePhase2(void);
void _autopilotPluginReadyChanged(bool pluginReady);
private:
/// All access to singleton is through MultiVehicleManager::instance
MultiVehicleManager(QObject* parent = NULL);
~MultiVehicleManager();
bool _vehicleExists(int vehicleId);
bool _activeVehicleAvailable; ///< true: An active vehicle is available
bool _parameterReadyVehicleAvailable; ///< true: An active vehicle with ready parameters is available
Vehicle* _activeVehicle; ///< Currently active vehicle from a ui perspective
Vehicle* _vehicleBeingDeleted; ///< Vehicle being deleted in queued phases
Vehicle* _vehicleBeingSetActive; ///< Vehicle being set active in queued phases
QList<int> _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication
QMap<int, Vehicle*> _vehicleMap; ///< Map of vehicles keyed by id
UASWaypointManager* _offlineWaypointManager;
};
#endif
/*=====================================================================
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/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "Vehicle.h"
#include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h"
#include "LinkManager.h"
#include "FirmwarePlugin.h"
#include "AutoPilotPluginManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
: _id(vehicleId)
, _firmwareType(firmwareType)
, _uas(NULL)
{
_addLink(link);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(this, &Vehicle::_sendMessageOnThread, this, &Vehicle::_sendMessage, Qt::QueuedConnection);
_uas = new UAS(MAVLinkProtocol::instance(), this);
_firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(firmwareType);
_autopilotPlugin = AutoPilotPluginManager::instance()->newAutopilotPluginForVehicle(this);
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
if (message.sysid != _id) {
return;
}
if (!_containsLink(link)) {
_addLink(link);
}
_uas->receiveMessage(message);
}
bool Vehicle::_containsLink(LinkInterface* link)
{
foreach (SharedLinkInterface sharedLink, _links) {
if (sharedLink.data() == link) {
return true;
}
}
return false;
}
void Vehicle::_addLink(LinkInterface* link)
{
if (!_containsLink(link)) {
_links += LinkManager::instance()->sharedPointerForLink(link);
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &Vehicle::_linkDisconnected);
}
}
void Vehicle::_linkDisconnected(LinkInterface* link)
{
qCDebug(VehicleLog) << "_linkDisconnected:" << link->getName();
qCDebug(VehicleLog) << "link count:" << _links.count();
for (int i=0; i<_links.count(); i++) {
if (_links[i].data() == link) {
_links.removeAt(i);
break;
}
}
if (_links.count() == 0) {
emit allLinksDisconnected();
}
}
void Vehicle::sendMessage(mavlink_message_t message)
{
emit _sendMessageOnThread(message);
}
void Vehicle::_sendMessage(mavlink_message_t message)
{
// Emit message on all links that are currently connected
foreach (SharedLinkInterface sharedLink, _links) {
LinkInterface* link = sharedLink.data();
Q_ASSERT(link);
if (link->isConnected()) {
MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
// Write message into buffer, prepending start sign
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
if (link->isConnected()) {
link->writeBytes((const char*)buffer, len);
} else {
qWarning() << "Link not connected";
}
}
}
}
QList<LinkInterface*> Vehicle::links(void)
{
QList<LinkInterface*> list;
foreach (SharedLinkInterface sharedLink, _links) {
list += sharedLink.data();
}
return list;
}
/*=====================================================================
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/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef Vehicle_H
#define Vehicle_H
#include <QObject>
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "UAS.h"
class FirmwarePlugin;
class AutoPilotPlugin;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
class Vehicle : public QObject
{
Q_OBJECT
public:
Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType);
Q_PROPERTY(int id READ id CONSTANT)
Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
// Property accesors
int id(void) { return _id; }
MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
/// Sends this specified message to all links accociated with this vehicle
void sendMessage(mavlink_message_t message);
/// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
UAS* uas(void) { return _uas; }
/// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; }
QList<LinkInterface*> links(void);
signals:
void allLinksDisconnected(void);
/// Used internally to move sendMessage call to main thread
void _sendMessageOnThread(mavlink_message_t message);
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _linkDisconnected(LinkInterface* link);
void _sendMessage(mavlink_message_t message);
private:
bool _containsLink(LinkInterface* link);
void _addLink(LinkInterface* link);
int _id; ///< Mavlink system id
MAV_AUTOPILOT _firmwareType;
FirmwarePlugin* _firmwarePlugin;
AutoPilotPlugin* _autopilotPlugin;
/// List of all links associated with this vehicle. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList<SharedLinkInterface> _links;
UAS* _uas;
};
#endif
...@@ -42,23 +42,9 @@ ...@@ -42,23 +42,9 @@
#include <QDebug> #include <QDebug>
SetupView::SetupView(QWidget* parent) : SetupView::SetupView(QWidget* parent) :
QGCQmlWidgetHolder(parent), QGCQmlWidgetHolder(parent)
_uasCurrent(NULL),
_initComplete(false),
_readyAutopilot(NULL)
{ {
#ifdef __mobile__
_showFirmware = false;
#else
_showFirmware = true;
#endif
connect(UASManager::instance(), &UASManager::activeUASSet, this, &SetupView::_setActiveUAS);
getRootContext()->setContextProperty("controller", this);
setSource(QUrl::fromUserInput("qrc:/qml/SetupView.qml")); setSource(QUrl::fromUserInput("qrc:/qml/SetupView.qml"));
_setActiveUAS(UASManager::instance()->getActiveUAS());
} }
SetupView::~SetupView() SetupView::~SetupView()
...@@ -66,37 +52,6 @@ SetupView::~SetupView() ...@@ -66,37 +52,6 @@ SetupView::~SetupView()
} }
void SetupView::_setActiveUAS(UASInterface* uas)
{
if (_uasCurrent) {
disconnect(_autopilot.data(), &AutoPilotPlugin::pluginReadyChanged, this, &SetupView::_pluginReadyChanged);
}
_pluginReadyChanged(false);
_uasCurrent = uas;
if (_uasCurrent) {
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uasCurrent);
if (_autopilot.data()->pluginReady()) {
_pluginReadyChanged(_autopilot.data()->pluginReady());
}
connect(_autopilot.data(), &AutoPilotPlugin::pluginReadyChanged, this, &SetupView::_pluginReadyChanged);
}
}
void SetupView::_pluginReadyChanged(bool pluginReady)
{
if (pluginReady) {
_readyAutopilot = _autopilot.data();
emit autopilotChanged(_readyAutopilot);
} else {
_readyAutopilot = NULL;
emit autopilotChanged(NULL);
_autopilot.clear();
}
}
#ifdef UNITTEST_BUILD #ifdef UNITTEST_BUILD
void SetupView::showFirmware(void) void SetupView::showFirmware(void)
{ {
...@@ -141,8 +96,3 @@ void SetupView::showVehicleComponentSetup(VehicleComponent* vehicleComponent) ...@@ -141,8 +96,3 @@ void SetupView::showVehicleComponentSetup(VehicleComponent* vehicleComponent)
Q_UNUSED(success); Q_UNUSED(success);
} }
#endif #endif
AutoPilotPlugin* SetupView::autopilot(void)
{
return _readyAutopilot;
}
...@@ -43,31 +43,12 @@ public: ...@@ -43,31 +43,12 @@ public:
explicit SetupView(QWidget* parent = 0); explicit SetupView(QWidget* parent = 0);
~SetupView(); ~SetupView();
Q_PROPERTY(AutoPilotPlugin* autopilot READ autopilot NOTIFY autopilotChanged)
Q_PROPERTY (bool showFirmware MEMBER _showFirmware CONSTANT)
#ifdef UNITTEST_BUILD #ifdef UNITTEST_BUILD
void showFirmware(void); void showFirmware(void);
void showParameters(void); void showParameters(void);
void showSummary(void); void showSummary(void);
void showVehicleComponentSetup(VehicleComponent* vehicleComponent); void showVehicleComponentSetup(VehicleComponent* vehicleComponent);
#endif #endif
AutoPilotPlugin* autopilot(void);
signals:
void autopilotChanged(AutoPilotPlugin* autopilot);
private slots:
void _setActiveUAS(UASInterface* uas);
void _pluginReadyChanged(bool pluginReady);
private:
UASInterface* _uasCurrent;
bool _initComplete; ///< true: parameters are ready and ui has been setup
QSharedPointer<AutoPilotPlugin> _autopilot; // Shared pointer to prevent shutdown ordering problems
AutoPilotPlugin* _readyAutopilot; // NULL if autopilot is not yet read
bool _showFirmware;
}; };
#endif #endif
...@@ -25,13 +25,14 @@ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. ...@@ -25,13 +25,14 @@ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
/// @brief Setup View /// @brief Setup View
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QGroundControl.AutoPilotPlugin 1.0 import QGroundControl.AutoPilotPlugin 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0
Rectangle { Rectangle {
id: topLevel id: topLevel
...@@ -52,7 +53,7 @@ Rectangle { ...@@ -52,7 +53,7 @@ Rectangle {
function showSummaryPanel() function showSummaryPanel()
{ {
if (controller.autopilot) { if (multiVehicleManager.parameterReadyVehicleAvailable) {
panelLoader.source = "VehicleSummary.qml"; panelLoader.source = "VehicleSummary.qml";
} else { } else {
panelLoader.sourceComponent = disconnectedVehicleSummaryComponent panelLoader.sourceComponent = disconnectedVehicleSummaryComponent
...@@ -61,8 +62,8 @@ Rectangle { ...@@ -61,8 +62,8 @@ Rectangle {
function showFirmwarePanel() function showFirmwarePanel()
{ {
if (controller.showFirmware) { if (!ScreenTools.isMobile) {
if (controller.autopilot && controller.autopilot.armed) { if (multiVehicleManager.activeVehicleAvailable && multiVehicleManager.activeVehicle.autopilot.armed) {
messagePanelText = armedVehicleText messagePanelText = armedVehicleText
panelLoader.sourceComponent = messagePanelComponent panelLoader.sourceComponent = messagePanelComponent
} else { } else {
...@@ -78,7 +79,7 @@ Rectangle { ...@@ -78,7 +79,7 @@ Rectangle {
function showVehicleComponentPanel(vehicleComponent) function showVehicleComponentPanel(vehicleComponent)
{ {
if (controller.autopilot.armed) { if (multiVehicleManager.activeVehicle.autopilot.armed) {
messagePanelText = armedVehicleText messagePanelText = armedVehicleText
panelLoader.sourceComponent = messagePanelComponent panelLoader.sourceComponent = messagePanelComponent
} else { } else {
...@@ -91,17 +92,17 @@ Rectangle { ...@@ -91,17 +92,17 @@ Rectangle {
} }
} }
Component.onCompleted: showSummaryPanel()
Connections { Connections {
target: controller target: multiVehicleManager
onAutopilotChanged: { onParameterReadyVehicleAvailableChanged: {
summaryButton.checked = true summaryButton.checked = true
showSummaryPanel() showSummaryPanel()
} }
} }
Component.onCompleted: showSummaryPanel()
Component { Component {
id: disconnectedVehicleSummaryComponent id: disconnectedVehicleSummaryComponent
...@@ -163,14 +164,14 @@ Rectangle { ...@@ -163,14 +164,14 @@ Rectangle {
imageResource: "/qmlimages/FirmwareUpgradeIcon.png" imageResource: "/qmlimages/FirmwareUpgradeIcon.png"
setupIndicator: false setupIndicator: false
exclusiveGroup: setupButtonGroup exclusiveGroup: setupButtonGroup
visible: controller.showFirmware visible: !ScreenTools.isMobile
text: "FIRMWARE" text: "FIRMWARE"
onClicked: showFirmwarePanel() onClicked: showFirmwarePanel()
} }
Repeater { Repeater {
model: controller.autopilot ? controller.autopilot.vehicleComponents : 0 model: multiVehicleManager.parameterReadyVehicleAvailable ? multiVehicleManager.activeVehicle.autopilot.vehicleComponents : 0
SubMenuButton { SubMenuButton {
width: buttonWidth width: buttonWidth
...@@ -187,7 +188,7 @@ Rectangle { ...@@ -187,7 +188,7 @@ Rectangle {
width: buttonWidth width: buttonWidth
setupIndicator: false setupIndicator: false
exclusiveGroup: setupButtonGroup exclusiveGroup: setupButtonGroup
visible: controller.autopilot visible: multiVehicleManager.parameterReadyVehicleAvailable
text: "PARAMETERS" text: "PARAMETERS"
onClicked: showParametersPanel() onClicked: showParametersPanel()
...@@ -202,7 +203,5 @@ Rectangle { ...@@ -202,7 +203,5 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
anchors.top: parent.top anchors.top: parent.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
property var autopilot: controller.autopilot
} }
} }
...@@ -29,7 +29,7 @@ ...@@ -29,7 +29,7 @@
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "SetupView.h" #include "SetupView.h"
#include "UASManager.h" #include "UASManager.h"
#include "AutoPilotPluginManager.h" #include "MultiVehicleManager.h"
UT_REGISTER_TEST(SetupViewTest) UT_REGISTER_TEST(SetupViewTest)
...@@ -69,17 +69,16 @@ void SetupViewTest::_clickThrough_test(void) ...@@ -69,17 +69,16 @@ void SetupViewTest::_clickThrough_test(void)
link->setAutopilotType(MAV_AUTOPILOT_PX4); link->setAutopilotType(MAV_AUTOPILOT_PX4);
LinkManager::instance()->_addLink(link); LinkManager::instance()->_addLink(link);
linkMgr->connectLink(link); linkMgr->connectLink(link);
QTest::qWait(5000); // Give enough time for UI to settle and heartbeats to go through
// Wait for the Vehicle to get created
QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QCOMPARE(spyVehicle.wait(5000), true);
QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable());
QVERIFY(MultiVehicleManager::instance()->activeVehicle());
AutoPilotPlugin* autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()).data(); AutoPilotPlugin* autopilot = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin();
Q_ASSERT(autopilot); Q_ASSERT(autopilot);
QSignalSpy spyPlugin(autopilot, SIGNAL(pluginReadyChanged(bool)));
if (!autopilot->pluginReady()) {
QCOMPARE(spyPlugin.wait(60000), true);
}
Q_ASSERT(autopilot->pluginReady());
// Switch to the Setup view // Switch to the Setup view
_mainToolBar->onSetupView(); _mainToolBar->onSetupView();
QTest::qWait(1000); QTest::qWait(1000);
......
...@@ -21,14 +21,15 @@ ...@@ -21,14 +21,15 @@
======================================================================*/ ======================================================================*/
import QtQuick 2.2 import QtQuick 2.2
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2 import QtQuick.Controls.Styles 1.2
import QGroundControl.FactSystem 1.0 import QGroundControl.FactSystem 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0
Rectangle { Rectangle {
width: 600 width: 600
...@@ -64,7 +65,7 @@ Rectangle { ...@@ -64,7 +65,7 @@ Rectangle {
"Below you will find a summary of the settings for your vehicle. To the left are the setup menus for each component." : "Below you will find a summary of the settings for your vehicle. To the left are the setup menus for each component." :
"WARNING: Your vehicle requires setup prior to flight. Please resolve the items marked in red using the menu on the left." "WARNING: Your vehicle requires setup prior to flight. Please resolve the items marked in red using the menu on the left."
property bool setupComplete: autopilot && autopilot.setupComplete property bool setupComplete: multiVehicleManager.activeVehicle.autopilot.setupComplete
} }
Item { Item {
...@@ -78,7 +79,8 @@ Rectangle { ...@@ -78,7 +79,8 @@ Rectangle {
spacing: 10 spacing: 10
Repeater { Repeater {
model: autopilot ? autopilot.vehicleComponents : 0 model: multiVehicleManager.activeVehicle.autopilot.vehicleComponents
// Outer summary item rectangle // Outer summary item rectangle
Rectangle { Rectangle {
......
...@@ -22,7 +22,7 @@ ...@@ -22,7 +22,7 @@
======================================================================*/ ======================================================================*/
#include "CustomCommandWidgetController.h" #include "CustomCommandWidgetController.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
...@@ -34,7 +34,7 @@ const char* CustomCommandWidgetController::_settingsKey = "CustomCommand.QmlFile ...@@ -34,7 +34,7 @@ const char* CustomCommandWidgetController::_settingsKey = "CustomCommand.QmlFile
CustomCommandWidgetController::CustomCommandWidgetController(void) : CustomCommandWidgetController::CustomCommandWidgetController(void) :
_uas(NULL) _uas(NULL)
{ {
_uas = UASManager::instance()->getActiveUAS(); _uas = MultiVehicleManager::instance()->activeVehicle()->uas();
Q_ASSERT(_uas); Q_ASSERT(_uas);
QSettings settings; QSettings settings;
......
...@@ -23,53 +23,33 @@ ...@@ -23,53 +23,33 @@
#include "ViewWidgetController.h" #include "ViewWidgetController.h"
#include "UASManager.h" #include "UASManager.h"
#include "AutoPilotPluginManager.h" #include "MultiVehicleManager.h"
ViewWidgetController::ViewWidgetController(void) : ViewWidgetController::ViewWidgetController(void) :
_autopilot(NULL), _autopilot(NULL),
_uas(NULL) _uas(NULL)
{ {
_uasManager = UASManager::instance(); connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &ViewWidgetController::_vehicleAvailable);
Q_ASSERT(_uasManager);
connect(_uasManager, &UASManagerInterface::activeUASSet, this, &ViewWidgetController::_activeUasChanged);
} }
void ViewWidgetController::_activeUasChanged(UASInterface* currentUas) void ViewWidgetController::_vehicleAvailable(bool available)
{ {
if (currentUas != _uas) { if (_uas) {
if (_uas) { _uas = NULL;
disconnect(_autopilot, &AutoPilotPlugin::pluginReadyChanged, this, &ViewWidgetController::_pluginReadyChanged); _autopilot = NULL;
_uas = NULL; emit pluginDisconnected();
_autopilot = NULL; }
emit pluginDisconnected();
} if (available) {
Vehicle* vehicle = MultiVehicleManager::instance()->activeVehicle();
if (currentUas) {
_uas = currentUas; _uas = vehicle->uas();
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(currentUas).data(); _autopilot = vehicle->autopilotPlugin();
Q_ASSERT(_autopilot); Q_ASSERT(_autopilot);
emit pluginConnected(QVariant::fromValue(_autopilot));
connect(_autopilot, &AutoPilotPlugin::pluginReadyChanged, this, &ViewWidgetController::_pluginReadyChanged); }
if (_autopilot->pluginReady()) {
_pluginReadyChanged(true);
}
}
}
} }
void ViewWidgetController::_pluginReadyChanged(bool pluginReady)
{
Q_ASSERT(_autopilot);
if (pluginReady) {
emit pluginConnected(QVariant::fromValue(_autopilot));
} else {
_activeUasChanged(NULL);
}
}
Q_INVOKABLE void ViewWidgetController::checkForVehicle(void) Q_INVOKABLE void ViewWidgetController::checkForVehicle(void)
{ {
_activeUasChanged(_uasManager->getActiveUAS()); _vehicleAvailable(MultiVehicleManager::instance()->activeVehicle());
} }
...@@ -29,6 +29,7 @@ ...@@ -29,6 +29,7 @@
#include "UASInterface.h" #include "UASInterface.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "UASManagerInterface.h" #include "UASManagerInterface.h"
#include "Vehicle.h"
class ViewWidgetController : public QObject class ViewWidgetController : public QObject
{ {
...@@ -44,12 +45,10 @@ signals: ...@@ -44,12 +45,10 @@ signals:
void pluginDisconnected(void); void pluginDisconnected(void);
private slots: private slots:
void _activeUasChanged(UASInterface* UAS); void _vehicleAvailable(bool available);
void _pluginReadyChanged(bool pluginReady);
private: private:
AutoPilotPlugin* _autopilot; AutoPilotPlugin* _autopilot;
UASManagerInterface* _uasManager;
UASInterface* _uas; UASInterface* _uas;
}; };
......
...@@ -20,16 +20,15 @@ ...@@ -20,16 +20,15 @@
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UAS.h" #include "UAS.h"
#include "configuration.h" #include "configuration.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
#include "QGC.h" #include "QGC.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "MultiVehicleManager.h"
Q_DECLARE_METATYPE(mavlink_message_t) Q_DECLARE_METATYPE(mavlink_message_t)
IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol) IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol)
...@@ -342,57 +341,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -342,57 +341,13 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
} }
} }
// ORDER MATTERS HERE! if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
// If the matching UAS object does not yet exist, it has to be created // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
// before emitting the packetReceived signal
UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);
// Check and (if necessary) create UAS object
if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
{
// ORDER MATTERS HERE!
// The UAS object has first to be created and connected,
// only then the rest of the application can be made aware
// of its existence, as it only then can send and receive
// it's first messages.
// Check if the UAS has the same id like this system
if (message.sysid == getSystemId())
{
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
}
// Create a new UAS based on the heartbeat received
// Todo dynamically load plugin at run-time for MAV
// WIKISEARCH:AUTOPILOT_TYPE_INSTANTIATION
// First create new UAS object
// Decode heartbeat message
mavlink_heartbeat_t heartbeat; mavlink_heartbeat_t heartbeat;
// Reset version field to 0
heartbeat.mavlink_version = 0;
mavlink_msg_heartbeat_decode(&message, &heartbeat); mavlink_msg_heartbeat_decode(&message, &heartbeat);
if (!MultiVehicleManager::instance()->notifyHeartbeatInfo(link, message.sysid, heartbeat)) {
// Check if the UAS has a different protocol version
if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
{
// Bring up dialog to inform user
if (!versionMismatchIgnore)
{
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("The MAVLink protocol version on the MAV and QGroundControl mismatch! "
"It is unsafe to use different MAVLink versions. "
"QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
versionMismatchIgnore = true;
}
// Ignore this message and continue gracefully
continue; continue;
} }
// Create a new UAS object
uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, (MAV_AUTOPILOT)heartbeat.autopilot);
} }
// Increase receive counter // Increase receive counter
......
...@@ -237,7 +237,7 @@ ...@@ -237,7 +237,7 @@
1 50 LNDMC_Z_VEL_MAX 0.3 9 1 50 LNDMC_Z_VEL_MAX 0.3 9
1 50 MAV_COMP_ID 50 6 1 50 MAV_COMP_ID 50 6
1 50 MAV_FWDEXTSP 1 6 1 50 MAV_FWDEXTSP 1 6
1 50 MAV_SYS_ID 1 6 1 50 MAV_SYS_ID 76 6
1 50 MAV_TYPE 2 6 1 50 MAV_TYPE 2 6
1 50 MAV_USEHILGPS 0 6 1 50 MAV_USEHILGPS 0 6
1 50 MC_ACRO_P_MAX 90 9 1 50 MC_ACRO_P_MAX 90 9
......
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
#include <QDebug> #include <QDebug>
#include <limits.h> #include <limits.h>
#include "UAS.h" #include "UAS.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "QGC.h" #include "QGC.h"
#include <QMutexLocker> #include <QMutexLocker>
#include <QSettings> #include <QSettings>
...@@ -49,7 +49,7 @@ JoystickInput::JoystickInput() : ...@@ -49,7 +49,7 @@ JoystickInput::JoystickInput() :
{ {
// Make sure we initialize with the correct UAS. // Make sure we initialize with the correct UAS.
setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
// Start this thread. This allows the Joystick Settings window to work correctly even w/o any UASes connected. // Start this thread. This allows the Joystick Settings window to work correctly even w/o any UASes connected.
start(); start();
...@@ -304,25 +304,14 @@ void JoystickInput::storeJoystickSettings() const ...@@ -304,25 +304,14 @@ void JoystickInput::storeJoystickSettings() const
settings.endGroup(); settings.endGroup();
} }
void JoystickInput::setActiveUAS(UASInterface* uas) void JoystickInput::_activeVehicleChanged(Vehicle* vehicle)
{ {
// Do nothing if the UAS hasn't changed.
if (uas == this->uas)
{
return;
}
// Only connect / disconnect is the UAS is of a controllable UAS class
UAS* tmp = 0;
if (this->uas) if (this->uas)
{ {
tmp = dynamic_cast<UAS*>(this->uas); disconnect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), uas, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8)));
if(tmp) disconnect(this, SIGNAL(actionTriggered(int)), uas, SLOT(triggerAction(int)));
{
disconnect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8)));
disconnect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int)));
}
uasCanReverse = false; uasCanReverse = false;
uas = NULL;
} }
// Save any settings for the last UAS // Save any settings for the last UAS
...@@ -331,23 +320,22 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -331,23 +320,22 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
storeJoystickSettings(); storeJoystickSettings();
} }
this->uas = uas; if (vehicle)
if (this->uas && (tmp = dynamic_cast<UAS*>(this->uas)))
{ {
connect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8))); uas = vehicle->uas();
connect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), uas, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8)));
qDebug() << "connected joystick"; qDebug() << "connected joystick";
connect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int))); connect(this, SIGNAL(actionTriggered(int)), uas, SLOT(triggerAction(int)));
uasCanReverse = tmp->systemCanReverse(); uasCanReverse = uas->systemCanReverse();
// Update the joystick settings for a new UAS. // Update the joystick settings for a new UAS.
autopilotType = uas->getAutopilotType(); autopilotType = uas->getAutopilotType();
systemType = uas->getSystemType(); systemType = uas->getSystemType();
} }
// Make sure any UI elements know we've updated the UAS. The UASManager signal is re-emitted here so that UI elements know to // Make sure any UI elements know we've updated the UAS. The signal is re-emitted here so that UI elements know to
// update their UAS-specific UI. // update their UAS-specific UI.
emit activeUASSet(uas); emit activeVehicleChanged(vehicle);
// Load any joystick-specific settings now that the UAS has changed. // Load any joystick-specific settings now that the UAS has changed.
if (joystickID > -1) if (joystickID > -1)
...@@ -412,8 +400,8 @@ void JoystickInput::init() ...@@ -412,8 +400,8 @@ void JoystickInput::init()
setActiveJoystick(activeJoystick); setActiveJoystick(activeJoystick);
// Now make sure we know what the current UAS is and track changes to it. // Now make sure we know what the current UAS is and track changes to it.
setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &JoystickInput::_activeVehicleChanged);
} }
void JoystickInput::shutdown() void JoystickInput::shutdown()
......
...@@ -52,7 +52,7 @@ This file is part of the PIXHAWK project ...@@ -52,7 +52,7 @@ This file is part of the PIXHAWK project
#include <SDL/SDL.h> #include <SDL/SDL.h>
#endif #endif
#include "UASInterface.h" #include "UAS.h"
struct JoystickSettings { struct JoystickSettings {
QMap<int, bool> axesInverted; ///< Whether each axis should be used inverted from what was reported. QMap<int, bool> axesInverted; ///< Whether each axis should be used inverted from what was reported.
...@@ -202,7 +202,7 @@ protected: ...@@ -202,7 +202,7 @@ protected:
bool done; bool done;
SDL_Joystick* joystick; SDL_Joystick* joystick;
UASInterface* uas; ///< Track the current UAS. UAS* uas; ///< Track the current UAS.
int autopilotType; ///< Cache the autopilotType int autopilotType; ///< Cache the autopilotType
int systemType; ///< Cache the systemType int systemType; ///< Cache the systemType
bool uasCanReverse; ///< Track whether the connect UAS can drive a reverse speed. bool uasCanReverse; ///< Track whether the connect UAS can drive a reverse speed.
...@@ -303,7 +303,7 @@ signals: ...@@ -303,7 +303,7 @@ signals:
/** @brief Signal that the UAS has been updated for this JoystickInput /** @brief Signal that the UAS has been updated for this JoystickInput
* Note that any UI updates should NOT query this object for joystick details. That should be done in response to the joystickSettingsChanged signal. * Note that any UI updates should NOT query this object for joystick details. That should be done in response to the joystickSettingsChanged signal.
*/ */
void activeUASSet(UASInterface*); void activeVehicleChanged(Vehicle* vehicle);
/** @brief Signals that new joystick-specific settings were changed. Useful for triggering updates that at dependent on the current joystick. */ /** @brief Signals that new joystick-specific settings were changed. Useful for triggering updates that at dependent on the current joystick. */
void joystickSettingsChanged(); void joystickSettingsChanged();
...@@ -314,8 +314,6 @@ signals: ...@@ -314,8 +314,6 @@ signals:
public slots: public slots:
/** @brief Enable or disable emitting the high-level control signals from the joystick. */ /** @brief Enable or disable emitting the high-level control signals from the joystick. */
void setEnabled(bool enable); void setEnabled(bool enable);
/** @brief Specify the UAS that this input should forward joystickChanged signals and buttonPresses to. */
void setActiveUAS(UASInterface* uas);
/** @brief Switch to a new joystick by ID number. Both buttons and axes are updated with the proper signals emitted. */ /** @brief Switch to a new joystick by ID number. Both buttons and axes are updated with the proper signals emitted. */
void setActiveJoystick(int id); void setActiveJoystick(int id);
/** @brief Switch calibration mode active */ /** @brief Switch calibration mode active */
...@@ -372,6 +370,9 @@ public slots: ...@@ -372,6 +370,9 @@ public slots:
{ {
mode = (JOYSTICK_MODE)newMode; mode = (JOYSTICK_MODE)newMode;
} }
private slots:
void _activeVehicleChanged(Vehicle* vehicle);
}; };
#endif // _JOYSTICKINPUT_H_ #endif // _JOYSTICKINPUT_H_
...@@ -8,7 +8,7 @@ ...@@ -8,7 +8,7 @@
#include "Mouse6dofInput.h" #include "Mouse6dofInput.h"
#include "UAS.h" #include "UAS.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#ifdef QGC_MOUSE_ENABLED_LINUX #ifdef QGC_MOUSE_ENABLED_LINUX
...@@ -38,7 +38,8 @@ Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) : ...@@ -38,7 +38,8 @@ Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) :
bValue(0.0), bValue(0.0),
cValue(0.0) cValue(0.0)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged);
// Connect 3DxWare SDK MotionEvent // Connect 3DxWare SDK MotionEvent
connect(mouseInput, SIGNAL(Move3d(std::vector<float>&)), this, SLOT(motion3DMouse(std::vector<float>&))); connect(mouseInput, SIGNAL(Move3d(std::vector<float>&)), this, SLOT(motion3DMouse(std::vector<float>&)));
connect(mouseInput, SIGNAL(On3dmouseKeyDown(int)), this, SLOT(button3DMouseDown(int))); connect(mouseInput, SIGNAL(On3dmouseKeyDown(int)), this, SLOT(button3DMouseDown(int)));
...@@ -62,7 +63,7 @@ Mouse6dofInput::Mouse6dofInput(QWidget* parent) : ...@@ -62,7 +63,7 @@ Mouse6dofInput::Mouse6dofInput(QWidget* parent) :
bValue(0.0), bValue(0.0),
cValue(0.0) cValue(0.0)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged);
if (!mouseActive) if (!mouseActive)
{ {
...@@ -111,27 +112,22 @@ Mouse6dofInput::~Mouse6dofInput() ...@@ -111,27 +112,22 @@ Mouse6dofInput::~Mouse6dofInput()
done = true; done = true;
} }
void Mouse6dofInput::setActiveUAS(UASInterface* uas) void Mouse6dofInput::_activeVehicleChanged(Vehicle* vehicle)
{ {
// Only connect / disconnect is the UAS is of a controllable UAS class
UAS* tmp = 0;
if (this->uas) if (this->uas)
{ {
tmp = dynamic_cast<UAS*>(this->uas); disconnect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), uas, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
if(tmp) // Todo: disconnect button mapping
{ uas = NULL;
disconnect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
// Todo: disconnect button mapping
}
} }
this->uas = uas; if (vehicle) {
uas = vehicle->uas();
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp) { connect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), uas, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double)));
connect(this, SIGNAL(mouse6dofChanged(double,double,double,double,double,double)), tmp, SLOT(setManual6DOFControlCommands(double,double,double,double,double,double))); // Todo: connect button mapping
// Todo: connect button mapping
} }
if (!isRunning()) if (!isRunning())
{ {
start(); start();
...@@ -141,7 +137,7 @@ void Mouse6dofInput::setActiveUAS(UASInterface* uas) ...@@ -141,7 +137,7 @@ void Mouse6dofInput::setActiveUAS(UASInterface* uas)
void Mouse6dofInput::init() void Mouse6dofInput::init()
{ {
// Make sure active UAS is set // Make sure active UAS is set
setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
} }
void Mouse6dofInput::run() void Mouse6dofInput::run()
......
...@@ -11,23 +11,24 @@ ...@@ -11,23 +11,24 @@
#include <QThread> #include <QThread>
#ifdef QGC_MOUSE_ENABLED_WIN #ifdef QGC_MOUSE_ENABLED_WIN
#include "Mouse3DInput.h" #include "Mouse3DInput.h"
#endif //QGC_MOUSE_ENABLED_WIN #endif //QGC_MOUSE_ENABLED_WIN
#include "UASInterface.h" #include "UAS.h"
#include "Vehicle.h"
class Mouse6dofInput : public QThread class Mouse6dofInput : public QThread
{ {
Q_OBJECT Q_OBJECT
public: public:
#ifdef QGC_MOUSE_ENABLED_WIN #ifdef QGC_MOUSE_ENABLED_WIN
Mouse6dofInput(Mouse3DInput* mouseInput); Mouse6dofInput(Mouse3DInput* mouseInput);
#endif //QGC_MOUSE_ENABLED_WIN #endif //QGC_MOUSE_ENABLED_WIN
#ifdef QGC_MOUSE_ENABLED_LINUX #ifdef QGC_MOUSE_ENABLED_LINUX
Mouse6dofInput(QWidget* parent); Mouse6dofInput(QWidget* parent);
#endif //QGC_MOUSE_ENABLED_LINUX #endif //QGC_MOUSE_ENABLED_LINUX
~Mouse6dofInput(); ~Mouse6dofInput();
void run(); void run();
...@@ -37,7 +38,7 @@ public: ...@@ -37,7 +38,7 @@ public:
protected: protected:
void init(); void init();
UASInterface* uas; UAS* uas;
bool done; bool done;
bool mouseActive; bool mouseActive;
bool translationActive; bool translationActive;
...@@ -77,18 +78,19 @@ signals: ...@@ -77,18 +78,19 @@ signals:
void mouseRotationActiveChanged(bool rotationEnable); void mouseRotationActiveChanged(bool rotationEnable);
public slots: public slots:
void setActiveUAS(UASInterface* uas); #ifdef QGC_MOUSE_ENABLED_WIN
#ifdef QGC_MOUSE_ENABLED_WIN
/** @brief Get a motion input from 3DMouse */ /** @brief Get a motion input from 3DMouse */
void motion3DMouse(std::vector<float> &motionData); void motion3DMouse(std::vector<float> &motionData);
/** @brief Get a button input from 3DMouse */ /** @brief Get a button input from 3DMouse */
void button3DMouseDown(int button); void button3DMouseDown(int button);
#endif //QGC_MOUSE_ENABLED_WIN #endif //QGC_MOUSE_ENABLED_WIN
#ifdef QGC_MOUSE_ENABLED_LINUX #ifdef QGC_MOUSE_ENABLED_LINUX
/** @brief Get an XEvent to check it for an 3DMouse event (motion or button) */ /** @brief Get an XEvent to check it for an 3DMouse event (motion or button) */
void handleX11Event(XEvent* event); void handleX11Event(XEvent* event);
#endif //QGC_MOUSE_ENABLED_LINUX #endif //QGC_MOUSE_ENABLED_LINUX
private slots:
void _activeVehicleChanged(Vehicle* vehicle);
}; };
#endif // MOUSE6DOFINPUT_H #endif // MOUSE6DOFINPUT_H
...@@ -25,7 +25,7 @@ ...@@ -25,7 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FileManagerTest.h" #include "FileManagerTest.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
//UT_REGISTER_TEST(FileManagerTest) //UT_REGISTER_TEST(FileManagerTest)
...@@ -51,13 +51,13 @@ void FileManagerTest::init(void) ...@@ -51,13 +51,13 @@ void FileManagerTest::init(void)
_fileServer = _mockLink->getFileServer(); _fileServer = _mockLink->getFileServer();
QVERIFY(_fileServer != NULL); QVERIFY(_fileServer != NULL);
// Wait or the UAS to show up // Wait or the Vehicle to show up
UASManagerInterface* uasManager = UASManager::instance(); MultiVehicleManager* vehicleManager = MultiVehicleManager::instance();
QSignalSpy spyUasCreate(uasManager, SIGNAL(UASCreated(UASInterface*))); QSignalSpy spyVehicleCreate(vehicleManager, SIGNAL(activeVehicleChanged(Vehicle*)));
if (!uasManager->getActiveUAS()) { if (!vehicleManager->activeVehicle()) {
QCOMPARE(spyUasCreate.wait(10000), true); QCOMPARE(spyVehicleCreate.wait(10000), true);
} }
UASInterface* uas = uasManager->getActiveUAS(); UASInterface* uas = vehicleManager->activeVehicle()->uas();
QVERIFY(uas != NULL); QVERIFY(uas != NULL);
_fileManager = uas->getFileManager(); _fileManager = uas->getFileManager();
......
...@@ -29,6 +29,7 @@ ...@@ -29,6 +29,7 @@
#include "MainWindowTest.h" #include "MainWindowTest.h"
#include "MockLink.h" #include "MockLink.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "MultiVehicleManager.h"
UT_REGISTER_TEST(MainWindowTest) UT_REGISTER_TEST(MainWindowTest)
...@@ -68,20 +69,12 @@ void MainWindowTest::_connectWindowClose_test(MAV_AUTOPILOT autopilot) ...@@ -68,20 +69,12 @@ void MainWindowTest::_connectWindowClose_test(MAV_AUTOPILOT autopilot)
link->setAutopilotType(autopilot); link->setAutopilotType(autopilot);
LinkManager::instance()->_addLink(link); LinkManager::instance()->_addLink(link);
if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Connect will pop a warning dialog
setExpectedMessageBox(QGCMessageBox::Ok);
}
linkMgr->connectLink(link); linkMgr->connectLink(link);
// Wait for the uas to work it's way through the various threads // Wait for the Vehicle to work it's way through the various threads
QSignalSpy spyUas(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*))); QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*)));
QCOMPARE(spyUas.wait(5000), true); QCOMPARE(spyVehicle.wait(5000), true);
if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
checkExpectedMessageBox();
}
// Cycle through all the top level views // Cycle through all the top level views
......
...@@ -32,6 +32,7 @@ ...@@ -32,6 +32,7 @@
#include "QGCTemporaryFile.h" #include "QGCTemporaryFile.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "UAS.h" #include "UAS.h"
#include "MultiVehicleManager.h"
UT_REGISTER_TEST(MavlinkLogTest) UT_REGISTER_TEST(MavlinkLogTest)
...@@ -146,12 +147,10 @@ void MavlinkLogTest::_connectLogWorker(bool arm) ...@@ -146,12 +147,10 @@ void MavlinkLogTest::_connectLogWorker(bool arm)
// Wait for the uas to work it's way through the various threads // Wait for the uas to work it's way through the various threads
QSignalSpy spyUas(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*))); QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*)));
QCOMPARE(spyUas.wait(5000), true); QCOMPARE(spyVehicle.wait(5000), true);
UASInterface* uasInterface = UASManager::instance()->getActiveUAS(); UAS* uas = MultiVehicleManager::instance()->activeUas();
QVERIFY(uasInterface);
UAS* uas = dynamic_cast<UAS*>(uasInterface);
QVERIFY(uas); QVERIFY(uas);
QDir logSaveDir; QDir logSaveDir;
......
...@@ -23,8 +23,7 @@ ...@@ -23,8 +23,7 @@
#include "PX4RCCalibrationTest.h" #include "PX4RCCalibrationTest.h"
#include "RadioComponentController.h" #include "RadioComponentController.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include "AutoPilotPluginManager.h"
/// @file /// @file
/// @brief QRadioComponentController Widget unit test /// @brief QRadioComponentController Widget unit test
...@@ -154,16 +153,15 @@ void RadioConfigTest::init(void) ...@@ -154,16 +153,15 @@ void RadioConfigTest::init(void)
Q_CHECK_PTR(_mockLink); Q_CHECK_PTR(_mockLink);
LinkManager::instance()->_addLink(_mockLink); LinkManager::instance()->_addLink(_mockLink);
LinkManager::instance()->connectLink(_mockLink); LinkManager::instance()->connectLink(_mockLink);
QTest::qWait(5000); // Give enough time for UI to settle and heartbeats to go through
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()).data(); // Wait for the Vehicle to get created
Q_ASSERT(_autopilot); QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QCOMPARE(spyVehicle.wait(5000), true);
QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable());
QVERIFY(MultiVehicleManager::instance()->activeVehicle());
QSignalSpy spyPlugin(_autopilot, SIGNAL(pluginReadyChanged(bool))); _autopilot = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin();
if (!_autopilot->pluginReady()) { Q_ASSERT(_autopilot);
QCOMPARE(spyPlugin.wait(60000), true);
}
Q_ASSERT(_autopilot->pluginReady());
// This will instatiate the widget with an active uas with ready parameters // This will instatiate the widget with an active uas with ready parameters
_calWidget = new QGCQmlWidgetHolder(); _calWidget = new QGCQmlWidgetHolder();
......
#include "UASUnitTest.h"
#include <stdio.h>
#include <QObject>
UT_REGISTER_TEST(UASUnitTest)
UASUnitTest::UASUnitTest()
{
}
//This function is called after every test
void UASUnitTest::init()
{
UnitTest::init();
_mavlink = new MAVLinkProtocol();
_uas = new UAS(_mavlink, UASID);
_uas->deleteSettings();
}
//this function is called after every test
void UASUnitTest::cleanup()
{
delete _uas;
_uas = NULL;
delete _mavlink;
_mavlink = NULL;
UnitTest::cleanup();
}
void UASUnitTest::getUASID_test()
{
// Test a default ID of zero is assigned
UAS* uas2 = new UAS(_mavlink);
QCOMPARE(uas2->getUASID(), 0);
delete uas2;
// Test that the chosen ID was assigned at construction
QCOMPARE(_uas->getUASID(), UASID);
// Make sure that no other ID was set
QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue);
QCOMPARE(_uas->getUASID(), 0);
// Make sure that ID >= 0
QCOMPARE(_uas->getUASID(), 100);
}
void UASUnitTest::getUASName_test()
{
// Test that the name is build as MAV + ID
QCOMPARE(_uas->getUASName(), "MAV " + QString::number(UASID));
}
void UASUnitTest::getUpTime_test()
{
UAS* uas2 = new UAS(_mavlink);
// Test that the uptime starts at zero to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
// Sleep for three seconds
QTest::qSleep(3000);
// Test that the up time is computed correctly to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0);
delete uas2;
}
void UASUnitTest::filterVoltage_test()
{
float verificar=_uas->filterVoltage(0.4f);
// We allow the voltage returned to be within a small delta
const float allowedDelta = 0.05f;
const float desiredVoltage = 7.36f;
QVERIFY(verificar > (desiredVoltage - allowedDelta) && verificar < (desiredVoltage + allowedDelta));
}
void UASUnitTest:: getAutopilotType_test()
{
int type = _uas->getAutopilotType();
// Verify that upon construction the autopilot is set to -1
QCOMPARE(type, -1);
}
void UASUnitTest::setAutopilotType_test()
{
_uas->setAutopilotType(2);
// Verify that the autopilot is set
QCOMPARE(_uas->getAutopilotType(), 2);
}
//verify that the correct status is returned if a certain statue is given to _uas
void UASUnitTest::getStatusForCode_test()
{
QString state, desc;
state = "";
desc = "";
_uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
_uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
_uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
QVERIFY(state == "BOOT");
_uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
QVERIFY(state == "CALIBRATING");
_uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
QVERIFY(state == "ACTIVE");
_uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
QVERIFY(state == "STANDBY");
_uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
QVERIFY(state == "CRITICAL");
_uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
QVERIFY(state == "EMERGENCY");
_uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
QVERIFY(state == "SHUTDOWN");
_uas->getStatusForCode(5325, state, desc);
QVERIFY(state == "UNKNOWN");
}
void UASUnitTest::getLocalX_test()
{
QCOMPARE(_uas->getLocalX(), 0.0);
}
void UASUnitTest::getLocalY_test()
{
QCOMPARE(_uas->getLocalY(), 0.0);
}
void UASUnitTest::getLocalZ_test()
{
QCOMPARE(_uas->getLocalZ(), 0.0);
}
void UASUnitTest::getLatitude_test()
{
QCOMPARE(_uas->getLatitude(), 0.0);
}
void UASUnitTest::getLongitude_test()
{
QCOMPARE(_uas->getLongitude(), 0.0);
}
void UASUnitTest::getAltitudeAMSL_test()
{
QCOMPARE(_uas->getAltitudeAMSL(), 0.0);
}
void UASUnitTest::getAltitudeRelative_test()
{
QCOMPARE(_uas->getAltitudeRelative(), 0.0);
}
void UASUnitTest::getRoll_test()
{
QCOMPARE(_uas->getRoll(), 0.0);
}
void UASUnitTest::getPitch_test()
{
QCOMPARE(_uas->getPitch(), 0.0);
}
void UASUnitTest::getYaw_test()
{
QCOMPARE(_uas->getYaw(), 0.0);
}
void UASUnitTest::getSelected_test()
{
QCOMPARE(_uas->getSelected(), false);
}
void UASUnitTest::getSystemType_test()
{ //check that system type is set to MAV_TYPE_GENERIC when initialized
QCOMPARE(_uas->getSystemType(), 0);
_uas->setSystemType(13);
QCOMPARE(_uas->getSystemType(), 13);
}
void UASUnitTest::getAirframe_test()
{
//when _uas is constructed, airframe is set to QGC_AIRFRAME_GENERIC
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
}
void UASUnitTest::setAirframe_test()
{
//check at construction, that airframe=0 (GENERIC)
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
//check that set airframe works
_uas->setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
//check that setAirframe will not assign a number to airframe, that is
//not defined in the enum
_uas->setAirframe(UASInterface::QGC_AIRFRAME_END_OF_ENUM);
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
}
void UASUnitTest::getWaypointList_test()
{
QList<Waypoint*> kk = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(kk.count(), 0);
Waypoint* wp = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
_uas->getWaypointManager()->addWaypointEditable(wp, true);
kk = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(kk.count(), 1);
wp = new Waypoint();
_uas->getWaypointManager()->addWaypointEditable(wp, false);
kk = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(kk.count(), 2);
_uas->getWaypointManager()->removeWaypoint(1);
kk = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(kk.count(), 1);
_uas->getWaypointManager()->removeWaypoint(0);
kk = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(kk.count(), 0);
qDebug()<<"disconnect SIGNAL waypointListChanged";
}
void UASUnitTest::getWaypoint_test()
{
Waypoint* wp = new Waypoint(0,5.6,2.0,3.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
_uas->getWaypointManager()->addWaypointEditable(wp, true);
QList<Waypoint*> wpList = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(wpList.count(), 1);
QCOMPARE(static_cast<quint16>(0), static_cast<Waypoint*>(wpList.at(0))->getId());
Waypoint* wp3 = new Waypoint(1, 5.6, 2.0, 3.0);
_uas->getWaypointManager()->addWaypointEditable(wp3, true);
wpList = _uas->getWaypointManager()->getWaypointEditableList();
Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));
QCOMPARE(wpList.count(), 2);
QCOMPARE(wp3->getX(), wp2->getX());
QCOMPARE(wp3->getY(), wp2->getY());
QCOMPARE(wp3->getZ(), wp2->getZ());
QCOMPARE(wpList.at(1)->getId(), static_cast<quint16>(1));
QCOMPARE(wp3->getFrame(), MAV_FRAME_GLOBAL);
QCOMPARE(wp3->getFrame(), wp2->getFrame());
delete wp3;
delete wp;
}
void UASUnitTest::signalWayPoint_test()
{
QSignalSpy spy(_uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
Waypoint* wp = new Waypoint(0,1.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
_uas->getWaypointManager()->addWaypointEditable(wp, true);
QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
_uas->getWaypointManager()->removeWaypoint(0);
QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
QSignalSpy spyDestroyed(_uas->getWaypointManager(), SIGNAL(destroyed()));
QVERIFY(spyDestroyed.isValid());
QCOMPARE( spyDestroyed.count(), 0 );
delete _uas;// delete(destroyed) _uas for validating
_uas = NULL;
QCOMPARE(spyDestroyed.count(), 1);// count destroyed _uas should are 1
_uas = new UAS(_mavlink, UASID);
QSignalSpy spy2(_uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
QCOMPARE(spy2.count(), 0);
Waypoint* wp2 = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
_uas->getWaypointManager()->addWaypointEditable(wp2, true);
QCOMPARE(spy2.count(), 1);
_uas->getWaypointManager()->clearWaypointList();
QList<Waypoint*> wpList = _uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(wpList.count(), 1);
delete _uas;
_uas = NULL;
delete wp2;
}
#ifndef UASUNITTEST_H
#define UASUNITTEST_H
#include "UAS.h"
#include "MAVLinkProtocol.h"
#include "SerialLink.h"
#include "UASInterface.h"
#include "UnitTest.h"
#include "LinkManager.h"
#include "UASWaypointManager.h"
#include "SerialLink.h"
#include "LinkInterface.h"
#define UASID 100
class UASUnitTest : public UnitTest
{
Q_OBJECT
public:
UASUnitTest(void);
private slots:
void init(void);
void cleanup(void);
void getUASID_test(void);
void getUASName_test(void);
void getUpTime_test(void);
void filterVoltage_test(void);
void getAutopilotType_test(void);
void setAutopilotType_test(void);
void getStatusForCode_test(void);
void getLocalX_test(void);
void getLocalY_test(void);
void getLocalZ_test(void);
void getLatitude_test(void);
void getLongitude_test(void);
void getAltitudeAMSL_test(void);
void getAltitudeRelative_test(void);
void getRoll_test(void);
void getPitch_test(void);
void getYaw_test(void);
void getSelected_test(void);
void getSystemType_test(void);
void getAirframe_test(void);
void setAirframe_test(void);
void getWaypointList_test(void);
void signalWayPoint_test(void);
void getWaypoint_test(void);
private:
MAVLinkProtocol* _mavlink;
UAS* _uas;
};
#endif
...@@ -25,6 +25,7 @@ ...@@ -25,6 +25,7 @@
#include "QGC.h" #include "QGC.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "Vehicle.h"
#include <QFile> #include <QFile>
#include <QDir> #include <QDir>
...@@ -32,17 +33,17 @@ ...@@ -32,17 +33,17 @@
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog") QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
FileManager::FileManager(QObject* parent, UASInterface* uas) : FileManager::FileManager(QObject* parent, Vehicle* vehicle) :
QObject(parent), QObject(parent),
_currentOperation(kCOIdle), _currentOperation(kCOIdle),
_mav(uas), _vehicle(vehicle),
_lastOutgoingSeqNumber(0), _lastOutgoingSeqNumber(0),
_activeSession(0), _activeSession(0),
_systemIdQGC(0) _systemIdQGC(0)
{ {
connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout); connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
_systemIdServer = _mav->getUASID(); _systemIdServer = _vehicle->id();
// Make sure we don't have bad structure packing // Make sure we don't have bad structure packing
Q_ASSERT(sizeof(RequestHeader) == 12); Q_ASSERT(sizeof(RequestHeader) == 12);
...@@ -720,7 +721,7 @@ void FileManager::_sendRequest(Request* request) ...@@ -720,7 +721,7 @@ void FileManager::_sendRequest(Request* request)
_systemIdQGC = MAVLinkProtocol::instance()->getSystemId(); _systemIdQGC = MAVLinkProtocol::instance()->getSystemId();
} }
Q_ASSERT(_mav); Q_ASSERT(_vehicle);
mavlink_msg_file_transfer_protocol_pack(_systemIdQGC, // QGC System ID mavlink_msg_file_transfer_protocol_pack(_systemIdQGC, // QGC System ID
0, // QGC Component ID 0, // QGC Component ID
&message, // Mavlink Message to pack into &message, // Mavlink Message to pack into
...@@ -729,5 +730,5 @@ void FileManager::_sendRequest(Request* request) ...@@ -729,5 +730,5 @@ void FileManager::_sendRequest(Request* request)
0, // Target component 0, // Target component
(uint8_t*)request); // Payload (uint8_t*)request); // Payload
_mav->sendMessage(message); _vehicle->sendMessage(message);
} }
...@@ -32,12 +32,14 @@ ...@@ -32,12 +32,14 @@
Q_DECLARE_LOGGING_CATEGORY(FileManagerLog) Q_DECLARE_LOGGING_CATEGORY(FileManagerLog)
class Vehicle;
class FileManager : public QObject class FileManager : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
FileManager(QObject* parent, UASInterface* uas); FileManager(QObject* parent, Vehicle* vehicle);
/// These methods are only used for testing purposes. /// These methods are only used for testing purposes.
bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); }; bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); };
...@@ -200,7 +202,7 @@ private: ...@@ -200,7 +202,7 @@ private:
OperationState _currentOperation; ///< Current operation of state machine OperationState _currentOperation; ///< Current operation of state machine
QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
UASInterface* _mav; Vehicle* _vehicle;
uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet
......
#include "QGCMAVLinkUASFactory.h"
#include "UASManager.h"
QGCMAVLinkUASFactory::QGCMAVLinkUASFactory(QObject *parent) :
QObject(parent)
{
}
UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInterface* link, int sysid, MAV_AUTOPILOT autopilotType)
{
UASInterface* uasInterface;
UAS* uasObject = new UAS(mavlink, sysid, autopilotType);
Q_CHECK_PTR(uasObject);
uasInterface = uasObject;
// Connect this robot to the UAS object
// It is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(mavlink, &MAVLinkProtocol::messageReceived, uasObject, &UAS::receiveMessage);
// Make UAS aware that this link can be used to communicate with the actual robot
uasInterface->addLink(link);
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uasInterface);
return uasInterface;
}
#ifndef QGCMAVLINKUASFACTORY_H
#define QGCMAVLINKUASFACTORY_H
#include <QObject>
#include "QGCMAVLink.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "LinkInterface.h"
// INCLUDE ALL MAV/UAS CLASSES USING MAVLINK
#include "UAS.h"
class QGCMAVLinkUASFactory : public QObject
{
Q_OBJECT
public:
explicit QGCMAVLinkUASFactory(QObject *parent = 0);
/** @brief Create a new UAS object using MAVLink as protocol */
static UASInterface* createUAS(MAVLinkProtocol* mavlink, LinkInterface* link, int sysid, MAV_AUTOPILOT autopilotType);
signals:
public slots:
};
#endif // QGCMAVLINKUASFACTORY_H
This diff is collapsed.
...@@ -47,6 +47,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -47,6 +47,8 @@ This file is part of the QGROUNDCONTROL project
Q_DECLARE_LOGGING_CATEGORY(UASLog) Q_DECLARE_LOGGING_CATEGORY(UASLog)
class Vehicle;
/** /**
* @brief A generic MAVLINK-connected MAV/UAV * @brief A generic MAVLINK-connected MAV/UAV
* *
...@@ -59,7 +61,7 @@ class UAS : public UASInterface ...@@ -59,7 +61,7 @@ class UAS : public UASInterface
{ {
Q_OBJECT Q_OBJECT
public: public:
UAS(MAVLinkProtocol* protocol, int id, MAV_AUTOPILOT autopilotType); UAS(MAVLinkProtocol* protocol, Vehicle* vehicle);
~UAS(); ~UAS();
float lipoFull; ///< 100% charged voltage float lipoFull; ///< 100% charged voltage
...@@ -87,9 +89,6 @@ public: ...@@ -87,9 +89,6 @@ public:
quint64 getUptime() const; quint64 getUptime() const;
/** @brief Add one measurement and get low-passed voltage */ /** @brief Add one measurement and get low-passed voltage */
float filterVoltage(float value) const; float filterVoltage(float value) const;
/** @brief Get the links associated with this robot */
QList<LinkInterface*> getLinks();
bool isLogReplay(void);
Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged) Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged)
Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged) Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged)
...@@ -317,7 +316,6 @@ public: ...@@ -317,7 +316,6 @@ public:
return yaw; return yaw;
} }
bool getSelected() const;
QVector3D getNedPosGlobalOffset() const QVector3D getNedPosGlobalOffset() const
{ {
return nedPosGlobalOffset; return nedPosGlobalOffset;
...@@ -393,10 +391,6 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -393,10 +391,6 @@ protected: //COMMENTS FOR TEST UNIT
int uasId; ///< Unique system ID int uasId; ///< Unique system ID
QMap<int, QString> components;///< IDs and names of all detected onboard components QMap<int, QString> components;///< IDs and names of all detected onboard components
/// List of all links associated with this UAS. We keep SharedLinkInterface objects which are QSharedPointer's in order to
/// maintain reference counts across threads. This way Link deletion works correctly.
QList<SharedLinkInterface> _links;
QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received QList<int> unknownPackets; ///< Packet IDs which are unknown and have been received
MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance MAVLinkProtocol* mavlink; ///< Reference to the MAVLink instance
float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs) float receiveDropRate; ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
...@@ -861,25 +855,14 @@ public slots: ...@@ -861,25 +855,14 @@ public slots:
void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw); void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
#endif #endif
/** @brief Add a link associated with this robot */
void addLink(LinkInterface* link);
/** @brief Receive a message from one of the communication links. */ /** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(LinkInterface* link, mavlink_message_t message); virtual void receiveMessage(mavlink_message_t message);
#ifdef QGC_PROTOBUF_ENABLED #ifdef QGC_PROTOBUF_ENABLED
/** @brief Receive a message from one of the communication links. */ /** @brief Receive a message from one of the communication links. */
virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message); virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif #endif
/** @brief Send a message over this link (to this or to all UAS on this link) */
void sendMessage(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void sendMessage(mavlink_message_t message);
/** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
void setSelected();
/** @brief Set current mode of operation, e.g. auto or manual, always uses the current arming status for safety reason */ /** @brief Set current mode of operation, e.g. auto or manual, always uses the current arming status for safety reason */
void setMode(uint8_t newBaseMode, uint32_t newCustomMode); void setMode(uint8_t newBaseMode, uint32_t newCustomMode);
...@@ -964,8 +947,6 @@ signals: ...@@ -964,8 +947,6 @@ signals:
void groundSpeedChanged(double val, QString name); void groundSpeedChanged(double val, QString name);
void airSpeedChanged(double val, QString name); void airSpeedChanged(double val, QString name);
void bearingToWaypointChanged(double val,QString name); void bearingToWaypointChanged(double val,QString name);
void _sendMessageOnThread(mavlink_message_t message);
void _sendMessageOnThreadLink(LinkInterface* link, mavlink_message_t message);
protected: protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0); quint64 getUnixTime(quint64 time=0);
...@@ -996,16 +977,9 @@ protected slots: ...@@ -996,16 +977,9 @@ protected slots:
void writeSettings(); void writeSettings();
/** @brief Read settings from disk */ /** @brief Read settings from disk */
void readSettings(); void readSettings();
/** @brief Send a message over this link (to this or to all UAS on this link) */
void _sendMessageLink(LinkInterface* link, mavlink_message_t message);
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
void _sendMessage(mavlink_message_t message);
private slots:
void _linkDisconnected(LinkInterface* link);
private: private:
bool _containsLink(LinkInterface* link); Vehicle* _vehicle;
}; };
......
...@@ -120,8 +120,6 @@ public: ...@@ -120,8 +120,6 @@ public:
virtual double getPitch() const = 0; virtual double getPitch() const = 0;
virtual double getYaw() const = 0; virtual double getYaw() const = 0;
virtual bool getSelected() const = 0;
virtual bool isArmed() const = 0; virtual bool isArmed() const = 0;
/** @brief Set the airframe of this MAV */ /** @brief Set the airframe of this MAV */
...@@ -132,11 +130,6 @@ public: ...@@ -132,11 +130,6 @@ public:
virtual FileManager* getFileManager() = 0; virtual FileManager* getFileManager() = 0;
/** @brief Send a message over this link (to this or to all UAS on this link) */
virtual void sendMessage(LinkInterface* link, mavlink_message_t message) = 0;
/** @brief Send a message over all links this UAS can be reached with (!= all links) */
virtual void sendMessage(mavlink_message_t message) = 0;
enum Airframe { enum Airframe {
QGC_AIRFRAME_GENERIC = 0, QGC_AIRFRAME_GENERIC = 0,
QGC_AIRFRAME_EASYSTAR, QGC_AIRFRAME_EASYSTAR,
...@@ -156,18 +149,6 @@ public: ...@@ -156,18 +149,6 @@ public:
QGC_AIRFRAME_END_OF_ENUM QGC_AIRFRAME_END_OF_ENUM
}; };
/**
* @brief Get the links associated with this robot
*
* @return List with all links this robot is associated with. Association is usually
* based on the fact that a message for this robot has been received through that
* interface. The LinkInterface can support multiple protocols.
**/
virtual QList<LinkInterface*> getLinks() = 0;
/// @returns true: UAS is connected to log replay link
virtual bool isLogReplay(void) = 0;
/** /**
* @brief Get the color for this UAS * @brief Get the color for this UAS
* *
...@@ -325,22 +306,6 @@ public slots: ...@@ -325,22 +306,6 @@ public slots:
/** @brief Set world frame origin / home position at this GPS position */ /** @brief Set world frame origin / home position at this GPS position */
virtual void setHomePosition(double lat, double lon, double alt) = 0; virtual void setHomePosition(double lat, double lon, double alt) = 0;
/**
* @brief Add a link to the list of current links
*
* Adding the link to the robot's internal link list will allow him so send its own messages
* over all registered links. Usually a link is added once a message for this particular robot
* has been received over a link, but adding could also be done manually.
* @warning Not all links should be added to all robots by default, because else all robots will
* attempt to send over all links, typically choking wireless serial links.
*/
virtual void addLink(LinkInterface* link) = 0;
/**
* @brief Set the current robot as focused in the user interface
*/
virtual void setSelected() = 0;
virtual void enableAllDataTransmission(int rate) = 0; virtual void enableAllDataTransmission(int rate) = 0;
virtual void enableRawSensorDataTransmission(int rate) = 0; virtual void enableRawSensorDataTransmission(int rate) = 0;
virtual void enableExtendedSystemStatusTransmission(int rate) = 0; virtual void enableExtendedSystemStatusTransmission(int rate) = 0;
...@@ -418,11 +383,6 @@ signals: ...@@ -418,11 +383,6 @@ signals:
void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z); void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z);
void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2); void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2);
/**
* @brief A misconfiguration has been detected by the UAS
*/
void misconfigurationDetected(UASInterface* uas);
/** @brief A text message from the system has been received */ /** @brief A text message from the system has been received */
void textMessageReceived(int uasid, int componentid, int severity, QString text); void textMessageReceived(int uasid, int componentid, int severity, QString text);
...@@ -601,8 +561,6 @@ signals: ...@@ -601,8 +561,6 @@ signals:
void heartbeatTimeout(bool timeout, unsigned int ms); void heartbeatTimeout(bool timeout, unsigned int ms);
/** @brief Name of system changed */ /** @brief Name of system changed */
void nameChanged(QString newName); void nameChanged(QString newName);
/** @brief System has been selected as focused system */
void systemSelected(bool selected);
/** @brief Core specifications have changed */ /** @brief Core specifications have changed */
void systemSpecsChanged(int uasId); void systemSpecsChanged(int uasId);
......
...@@ -19,6 +19,7 @@ ...@@ -19,6 +19,7 @@
#include "QGC.h" #include "QGC.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "MultiVehicleManager.h"
#define PI 3.1415926535897932384626433832795 #define PI 3.1415926535897932384626433832795
#define MEAN_EARTH_DIAMETER 12756274.0 #define MEAN_EARTH_DIAMETER 12756274.0
...@@ -28,7 +29,6 @@ IMPLEMENT_QGC_SINGLETON(UASManager, UASManagerInterface) ...@@ -28,7 +29,6 @@ IMPLEMENT_QGC_SINGLETON(UASManager, UASManagerInterface)
UASManager::UASManager(QObject* parent) : UASManager::UASManager(QObject* parent) :
UASManagerInterface(parent), UASManagerInterface(parent),
activeUAS(NULL),
offlineUASWaypointManager(NULL), offlineUASWaypointManager(NULL),
homeLat(47.3769), homeLat(47.3769),
homeLon(8.549444), homeLon(8.549444),
...@@ -42,20 +42,6 @@ UASManager::UASManager(QObject* parent) : ...@@ -42,20 +42,6 @@ UASManager::UASManager(QObject* parent) :
UASManager::~UASManager() UASManager::~UASManager()
{ {
storeSettings(); storeSettings();
Q_ASSERT_X(systems.count() == 0, "~UASManager", "_shutdown should have already removed all uas");
}
void UASManager::_shutdown(void)
{
QList<UASInterface*> uasList;
foreach(UASInterface* uas, systems) {
uasList.append(uas);
}
foreach(UASInterface* uas, uasList) {
removeUAS(uas);
}
} }
void UASManager::storeSettings() void UASManager::storeSettings()
...@@ -121,13 +107,8 @@ bool UASManager::setHomePositionAndNotify(double lat, double lon, double alt) ...@@ -121,13 +107,8 @@ bool UASManager::setHomePositionAndNotify(double lat, double lon, double alt)
// and checking for borders // and checking for borders
bool changed = setHomePosition(lat, lon, alt); bool changed = setHomePosition(lat, lon, alt);
if (changed) if (changed) {
{ MultiVehicleManager::instance()->setHomePositionForAllVehicles(homeLat, homeLon, homeAlt);
// Update all UAVs
foreach (UASInterface* mav, systems)
{
mav->setHomePosition(homeLat, homeLon, homeAlt);
}
} }
return changed; return changed;
...@@ -240,7 +221,7 @@ void UASManager::nedToWgs84(const double& x, const double& y, const double& z, d ...@@ -240,7 +221,7 @@ void UASManager::nedToWgs84(const double& x, const double& y, const double& z, d
void UASManager::uavChangedHomePosition(int uav, double lat, double lon, double alt) void UASManager::uavChangedHomePosition(int uav, double lat, double lon, double alt)
{ {
// Accept home position changes from the active UAS // Accept home position changes from the active UAS
if (uav == activeUAS->getUASID()) if (uav == MultiVehicleManager::instance()->activeVehicle()->id())
{ {
if (setHomePosition(lat, lon, alt)) if (setHomePosition(lat, lon, alt))
{ {
...@@ -258,202 +239,3 @@ void UASManager::uavChangedHomePosition(int uav, double lat, double lon, double ...@@ -258,202 +239,3 @@ void UASManager::uavChangedHomePosition(int uav, double lat, double lon, double
} }
} }
} }
void UASManager::addUAS(UASInterface* uas)
{
// WARNING: The active uas is set here
// and then announced below. This is necessary
// to make sure the getActiveUAS() function
// returns the UAS once the UASCreated() signal
// is emitted. The code is thus NOT redundant.
bool firstUAS = false;
if (activeUAS == NULL)
{
firstUAS = true;
activeUAS = uas;
}
// Only execute if there is no UAS at this index
if (!systems.contains(uas))
{
qDebug() << "Add new UAS: " << uas->getUASID();
systems.append(uas);
// Set home position on UAV if set in UI
// - this is done on a per-UAV basis
// Set home position in UI if UAV chooses a new one (caution! if multiple UAVs are connected, take care!)
connect(uas, SIGNAL(homePositionChanged(int,double,double,double)), this, SLOT(uavChangedHomePosition(int,double,double,double)));
emit UASCreated(uas);
}
// If there is no active UAS yet, set the first one as the active UAS
if (firstUAS)
{
setActiveUAS(uas);
// Call getActiveUASWaypointManager instead of referencing variable to make sure of creation
if (getActiveUASWaypointManager()->getWaypointEditableList().size() > 0)
{
if (QGCMessageBox::question(tr("Question"), tr("Do you want to append the offline waypoints to the ones currently on the UAV?"), QMessageBox::Yes, QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<offlineUASWaypointManager->getWaypointEditableList().size();i++)
{
Waypoint *wp = uas->getWaypointManager()->createWaypoint();
wp->setLatitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getAltitude());
}
}
offlineUASWaypointManager->deleteLater();
offlineUASWaypointManager = 0;
}
}
}
/**
* @brief The function that should be used when removing UASes from QGC. emits UASDeletect(UASInterface*) when triggered
* so that UI elements can update accordingly.
* @param uas The UAS to remove
*/
void UASManager::removeUAS(UASInterface* uas)
{
if (uas)
{
int listindex = systems.indexOf(uas);
// Remove this system from local data store.
systems.removeAt(listindex);
// If this is the active UAS, select a new one if one exists otherwise
// indicate that there are no active UASes.
if (uas == activeUAS)
{
if (systems.count())
{
setActiveUAS(systems.first());
}
else
{
setActiveUAS(NULL);
}
}
// Notify other UI elements that a UAS is being deleted before finally deleting it.
qDebug() << "Deleting UAS object: " << uas->getUASName();
emit UASDeleted(uas);
emit UASDeleted(uas->getUASID());
uas->deleteLater();
}
}
QList<UASInterface*> UASManager::getUASList()
{
return systems;
}
UASInterface* UASManager::getActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASInterface* UASManager::silentGetActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASWaypointManager *UASManager::getActiveUASWaypointManager()
{
if (activeUAS)
{
return activeUAS->getWaypointManager();
}
if (!offlineUASWaypointManager)
{
offlineUASWaypointManager = new UASWaypointManager(NULL);
}
return offlineUASWaypointManager;
}
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->launch();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::haltActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->halt();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::continueActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->go();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::returnActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->home();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::stopActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->emergencySTOP();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::killActiveUAS()
{
if (getActiveUAS()) activeUAS->emergencyKILL();
return (activeUAS);
}
bool UASManager::shutdownActiveUAS()
{
if (getActiveUAS()) activeUAS->shutdown();
return (activeUAS);
}
UASInterface* UASManager::getUASForId(int id)
{
UASInterface* system = NULL;
foreach(UASInterface* sys, systems) {
if (sys->getUASID() == id) {
system = sys;
}
}
// Return NULL if not found
return system;
}
void UASManager::setActiveUAS(UASInterface* uas)
{
// Signal components that the last UAS is no longer active.
activeUASMutex.lock();
if (activeUAS != NULL) {
emit activeUASStatusChanged(activeUAS, false);
emit activeUASStatusChanged(activeUAS->getUASID(), false);
}
activeUAS = uas;
activeUASMutex.unlock();
// And signal that a new UAS is.
emit activeUASSet(activeUAS);
if (activeUAS)
{
activeUAS->setSelected();
emit activeUASSetListIndex(systems.indexOf(activeUAS));
emit activeUASStatusChanged(activeUAS, true);
emit activeUASStatusChanged(activeUAS->getUASID(), true);
}
}
...@@ -55,31 +55,6 @@ class UASManager : public UASManagerInterface ...@@ -55,31 +55,6 @@ class UASManager : public UASManagerInterface
DECLARE_QGC_SINGLETON(UASManager, UASManagerInterface) DECLARE_QGC_SINGLETON(UASManager, UASManagerInterface)
public: public:
/**
* @brief Get the currently selected UAS
*
* @return NULL pointer if no UAS exists, active UAS else
**/
UASInterface* getActiveUAS();
/**
* @brief getActiveUASWaypointManager
* @return uas->getUASWaypointManager(), or if not connected, a singleton instance of a UASWaypointManager.
*/
UASWaypointManager *getActiveUASWaypointManager();
UASInterface* silentGetActiveUAS();
/**
* @brief Get the UAS with this id
*
* Although not enforced by this implementation, the IDs are constrained to be
* in the range of 1 - 127 by the MAVLINK protocol.
*
* @param id unique system / aircraft id
* @return UAS with the given ID, NULL pointer else
**/
UASInterface* getUASForId(int id);
QList<UASInterface*> getUASList();
/** @brief Get home position latitude */ /** @brief Get home position latitude */
double getHomeLatitude() const { double getHomeLatitude() const {
return homeLat; return homeLat;
...@@ -145,88 +120,6 @@ public: ...@@ -145,88 +120,6 @@ public:
public slots: public slots:
/**
* @brief Add a new UAS to the list
*
* This command will only be executed if this UAS does not yet exist.
* @param UAS unmanned air system to add
**/
void addUAS(UASInterface* UAS);
/** @brief Remove a system from the list. If this is the active UAS, it switches to another one calling setActiveUAS. Also triggers the UAS to kill itself. */
void removeUAS(UASInterface* uas);
/**
* @brief Set a UAS as currently selected. NULL is a valid value for when no other valid UAS's are available.
*
* @param UAS Unmanned Air System to set
**/
void setActiveUAS(UASInterface* UAS);
/**
* @brief Launch the active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command starts
* the launch sequence.
*
* @return True if the UAS could be launched, false else
*/
bool launchActiveUAS();
bool haltActiveUAS();
bool continueActiveUAS();
/**
* @brief Land the active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command starts
* the land sequence. Depending on the onboard control, this could mean
* returning to the landing spot as well as descending on the current
* position.
*
* @return True if the UAS could be landed, false else
*/
bool returnActiveUAS();
/**
* @brief EMERGENCY: Stop active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command
* starts an emergency landing. Depending on the onboard control,
* this usually means descending rapidly on the current position.
*
* @warning This command can severely damage the UAS!
*
* @return True if the UAS could be landed, false else
*/
bool stopActiveUAS();
/**
* @brief EMERGENCY: Kill active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command
* shuts off all onboard motors immediately. This leads to a
* system crash, but might prevent external damage, e.g. to people.
* This command is secured by an additional popup message window.
*
* @warning THIS COMMAND RESULTS IN THE LOSS OF THE SYSTEM!
*
* @return True if the UAS could be landed, false else
*/
bool killActiveUAS();
/** @brief Shut down the onboard operating system down */
bool shutdownActiveUAS();
/** @brief Set the current home position, but do not change it on the UAVs */ /** @brief Set the current home position, but do not change it on the UAVs */
bool setHomePosition(double lat, double lon, double alt); bool setHomePosition(double lat, double lon, double alt);
...@@ -243,15 +136,10 @@ public slots: ...@@ -243,15 +136,10 @@ public slots:
void loadSettings(); void loadSettings();
/** @brief Store settings */ /** @brief Store settings */
void storeSettings(); void storeSettings();
void _shutdown(void);
protected: protected:
QList<UASInterface*> systems;
UASInterface* activeUAS;
UASWaypointManager *offlineUASWaypointManager; UASWaypointManager *offlineUASWaypointManager;
QMutex activeUASMutex;
double homeLat; double homeLat;
double homeLon; double homeLon;
double homeAlt; double homeAlt;
......
...@@ -57,11 +57,6 @@ class UASManagerInterface : public QGCSingleton ...@@ -57,11 +57,6 @@ class UASManagerInterface : public QGCSingleton
Q_OBJECT Q_OBJECT
public: public:
virtual UASInterface* getActiveUAS() = 0;
virtual UASWaypointManager *getActiveUASWaypointManager() = 0;
virtual UASInterface* silentGetActiveUAS() = 0;
virtual UASInterface* getUASForId(int id) = 0;
virtual QList<UASInterface*> getUASList() = 0;
virtual double getHomeLatitude() const = 0; virtual double getHomeLatitude() const = 0;
virtual double getHomeLongitude() const = 0; virtual double getHomeLongitude() const = 0;
virtual double getHomeAltitude() const = 0; virtual double getHomeAltitude() const = 0;
...@@ -75,39 +70,14 @@ public: ...@@ -75,39 +70,14 @@ public:
virtual bool isInLocalNEDSafetyLimits(double x, double y, double z) = 0; virtual bool isInLocalNEDSafetyLimits(double x, double y, double z) = 0;
public slots: public slots:
virtual void addUAS(UASInterface* UAS) = 0;
virtual void removeUAS(UASInterface* uas) = 0;
virtual void setActiveUAS(UASInterface* UAS) = 0;
virtual bool launchActiveUAS() = 0;
virtual bool haltActiveUAS() = 0;
virtual bool continueActiveUAS() = 0;
virtual bool returnActiveUAS() = 0;
virtual bool stopActiveUAS() = 0;
virtual bool killActiveUAS() = 0;
virtual bool shutdownActiveUAS() = 0;
virtual bool setHomePosition(double lat, double lon, double alt) = 0; virtual bool setHomePosition(double lat, double lon, double alt) = 0;
virtual bool setHomePositionAndNotify(double lat, double lon, double alt) = 0; virtual bool setHomePositionAndNotify(double lat, double lon, double alt) = 0;
virtual void setLocalNEDSafetyBorders(double x1, double y1, double z1, double x2, double y2, double z2) = 0; virtual void setLocalNEDSafetyBorders(double x1, double y1, double z1, double x2, double y2, double z2) = 0;
virtual void uavChangedHomePosition(int uav, double lat, double lon, double alt) = 0; virtual void uavChangedHomePosition(int uav, double lat, double lon, double alt) = 0;
virtual void loadSettings() = 0; virtual void loadSettings() = 0;
virtual void storeSettings() = 0; virtual void storeSettings() = 0;
virtual void _shutdown(void) = 0;
signals: signals:
/** A new system was created */
void UASCreated(UASInterface* UAS);
/** A system was deleted */
void UASDeleted(UASInterface* UAS);
/** A system was deleted */
void UASDeleted(int systemId);
/** @brief The UAS currently under main operator control changed */
void activeUASSet(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
void activeUASSetListIndex(int listIndex);
/** @brief The UAS currently under main operator control changed */
void activeUASStatusChanged(UASInterface* UAS, bool active);
/** @brief The UAS currently under main operator control changed */
void activeUASStatusChanged(int systemId, bool active);
/** @brief Current home position changed */ /** @brief Current home position changed */
void homePositionChanged(double lat, double lon, double alt); void homePositionChanged(double lat, double lon, double alt);
......
...@@ -29,7 +29,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -29,7 +29,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h" #include "QGCApplication.h"
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
UASMessage::UASMessage(int componentid, int severity, QString text) UASMessage::UASMessage(int componentid, int severity, QString text)
{ {
...@@ -62,7 +62,7 @@ UASMessageHandler::UASMessageHandler(QObject *parent) ...@@ -62,7 +62,7 @@ UASMessageHandler::UASMessageHandler(QObject *parent)
, _normalCount(0) , _normalCount(0)
, _showErrorsInToolbar(false) , _showErrorsInToolbar(false)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASMessageHandler::_activeVehicleChanged);
emit textMessageReceived(NULL); emit textMessageReceived(NULL);
emit textMessageCountChanged(0); emit textMessageCountChanged(0);
} }
...@@ -86,10 +86,10 @@ void UASMessageHandler::clearMessages() ...@@ -86,10 +86,10 @@ void UASMessageHandler::clearMessages()
emit textMessageCountChanged(0); emit textMessageCountChanged(0);
} }
void UASMessageHandler::setActiveUAS(UASInterface* uas) void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle)
{ {
// If we were already attached to an autopilot, disconnect it. // If we were already attached to an autopilot, disconnect it.
if (_activeUAS && _activeUAS != uas) if (_activeUAS)
{ {
disconnect(_activeUAS, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(handleTextMessage(int,int,int,QString))); disconnect(_activeUAS, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(handleTextMessage(int,int,int,QString)));
_activeUAS = NULL; _activeUAS = NULL;
...@@ -97,8 +97,10 @@ void UASMessageHandler::setActiveUAS(UASInterface* uas) ...@@ -97,8 +97,10 @@ void UASMessageHandler::setActiveUAS(UASInterface* uas)
emit textMessageReceived(NULL); emit textMessageReceived(NULL);
} }
// And now if there's an autopilot to follow, set up the UI. // And now if there's an autopilot to follow, set up the UI.
if (uas) if (vehicle)
{ {
UAS* uas = vehicle->uas();
// Connect to the new UAS. // Connect to the new UAS.
clearMessages(); clearMessages();
_activeUAS = uas; _activeUAS = uas;
......
...@@ -35,6 +35,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -35,6 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMutex> #include <QMutex>
#include "QGCSingleton.h" #include "QGCSingleton.h"
#include "Vehicle.h"
class UASInterface; class UASInterface;
class UASMessageHandler; class UASMessageHandler;
...@@ -126,11 +127,6 @@ public: ...@@ -126,11 +127,6 @@ public:
void showErrorsInToolbar(void) { _showErrorsInToolbar = true; } void showErrorsInToolbar(void) { _showErrorsInToolbar = true; }
public slots: public slots:
/**
* @brief Set currently active UAS
* @param uas The current active UAS
*/
void setActiveUAS(UASInterface* uas);
/** /**
* @brief Handle text message from current active UAS * @brief Handle text message from current active UAS
* @param uasid UAS Id * @param uasid UAS Id
...@@ -152,6 +148,9 @@ signals: ...@@ -152,6 +148,9 @@ signals:
*/ */
void textMessageCountChanged(int count); void textMessageCountChanged(int count);
private slots:
void _activeVehicleChanged(Vehicle* vehicle);
private: private:
// Stores the UAS that we're currently receiving messages from. // Stores the UAS that we're currently receiving messages from.
UASInterface* _activeUAS; UASInterface* _activeUAS;
......
This diff is collapsed.
...@@ -38,8 +38,10 @@ This file is part of the QGROUNDCONTROL project ...@@ -38,8 +38,10 @@ This file is part of the QGROUNDCONTROL project
#include <QPointer> #include <QPointer>
#include "Waypoint.h" #include "Waypoint.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
class UAS; class UAS;
class UASInterface; class UASInterface;
class Vehicle;
/** /**
* @brief Implementation of the MAVLINK waypoint protocol * @brief Implementation of the MAVLINK waypoint protocol
...@@ -65,7 +67,7 @@ private: ...@@ -65,7 +67,7 @@ private:
}; ///< The possible states for the waypoint protocol }; ///< The possible states for the waypoint protocol
public: public:
UASWaypointManager(UAS* uas=NULL); ///< Standard constructor UASWaypointManager(Vehicle* vehicle, UAS* uas); ///< Standard constructor
~UASWaypointManager(); ~UASWaypointManager();
bool guidedModeSupported(); bool guidedModeSupported();
...@@ -171,7 +173,7 @@ private slots: ...@@ -171,7 +173,7 @@ private slots:
void _updateWPonTimer(void); ///< Starts requesting WP on timer timeout void _updateWPonTimer(void); ///< Starts requesting WP on timer timeout
private: private:
UAS* uas; ///< Reference to the corresponding UAS Vehicle* _vehicle;
quint32 current_retries; ///< The current number of retries left quint32 current_retries; ///< The current number of retries left
quint16 current_wp_id; ///< The last used waypoint ID in the current protocol transaction quint16 current_wp_id; ///< The last used waypoint ID in the current protocol transaction
quint16 current_count; ///< The number of waypoints in the current protocol transaction quint16 current_count; ///< The number of waypoints in the current protocol transaction
......
...@@ -19,13 +19,13 @@ ...@@ -19,13 +19,13 @@
#include <QMenu> #include <QMenu>
#include <QSettings> #include <QSettings>
#include <qmath.h> #include <qmath.h>
#include "UASManager.h"
#include "HDDisplay.h" #include "HDDisplay.h"
#include "ui_HDDisplay.h" #include "ui_HDDisplay.h"
#include "MG.h" #include "MG.h"
#include "QGC.h" #include "QGC.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include <QDebug> #include <QDebug>
#include "MultiVehicleManager.h"
HDDisplay::HDDisplay(const QStringList &plotList, QString title, QWidget *parent) : HDDisplay::HDDisplay(const QStringList &plotList, QString title, QWidget *parent) :
QGraphicsView(parent), QGraphicsView(parent),
...@@ -126,8 +126,8 @@ HDDisplay::HDDisplay(const QStringList &plotList, QString title, QWidget *parent ...@@ -126,8 +126,8 @@ HDDisplay::HDDisplay(const QStringList &plotList, QString title, QWidget *parent
if (font.family() != fontFamilyName) qDebug() << "ERROR! Font not loaded: " << fontFamilyName; if (font.family() != fontFamilyName) qDebug() << "ERROR! Font not loaded: " << fontFamilyName;
// Connect with UAS // Connect with UAS
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &HDDisplay::_activeVehicleChanged);
setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
} }
HDDisplay::~HDDisplay() HDDisplay::~HDDisplay()
...@@ -471,7 +471,7 @@ void HDDisplay::renderOverlay() ...@@ -471,7 +471,7 @@ void HDDisplay::renderOverlay()
* *
* @param uas the UAS/MAV to monitor/display with the HUD * @param uas the UAS/MAV to monitor/display with the HUD
*/ */
void HDDisplay::setActiveUAS(UASInterface* uas) void HDDisplay::_activeVehicleChanged(Vehicle* vehicle)
{ {
// Disconnect any previously connected active UAS // Disconnect any previously connected active UAS
if (this->uas != NULL) { if (this->uas != NULL) {
...@@ -479,10 +479,10 @@ void HDDisplay::setActiveUAS(UASInterface* uas) ...@@ -479,10 +479,10 @@ void HDDisplay::setActiveUAS(UASInterface* uas)
this->uas = NULL; this->uas = NULL;
} }
if (uas) { if (vehicle) {
this->uas = vehicle->uas();
// Now connect the new UAS // Now connect the new UAS
addSource(uas); addSource(uas);
this->uas = uas;
} }
} }
......
...@@ -42,6 +42,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -42,6 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include <cmath> #include <cmath>
#include "UASInterface.h" #include "UASInterface.h"
#include "Vehicle.h"
namespace Ui namespace Ui
{ {
...@@ -67,8 +68,6 @@ public slots: ...@@ -67,8 +68,6 @@ public slots:
/** @brief Update the HDD with new data */ /** @brief Update the HDD with new data */
void updateValue(const int uasId, const QString& name, const QString& unit, const QVariant &value, const quint64 msec); void updateValue(const int uasId, const QString& name, const QString& unit, const QVariant &value, const quint64 msec);
virtual void setActiveUAS(UASInterface* uas);
/** @brief Connects a source to the updateValue() signals */ /** @brief Connects a source to the updateValue() signals */
void addSource(QObject* obj); void addSource(QObject* obj);
/** @brief Disconnects a source to the updateValue() signals */ /** @brief Disconnects a source to the updateValue() signals */
...@@ -197,6 +196,9 @@ protected: ...@@ -197,6 +196,9 @@ protected:
QAction* setTitleAction; ///< Action setting the title QAction* setTitleAction; ///< Action setting the title
QAction* setColumnsAction; ///< Action setting the number of columns QAction* setColumnsAction; ///< Action setting the number of columns
bool valuesChanged; bool valuesChanged;
private slots:
void _activeVehicleChanged(Vehicle* vehicle);
private: private:
Ui::HDDisplay *m_ui; Ui::HDDisplay *m_ui;
......
...@@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDoubleSpinBox> #include <QDoubleSpinBox>
#include <QDebug> #include <QDebug>
#include "MultiVehicleManager.h"
#include "UASManager.h" #include "UASManager.h"
#include "HSIDisplay.h" #include "HSIDisplay.h"
#include "QGC.h" #include "QGC.h"
...@@ -178,16 +179,9 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -178,16 +179,9 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
// XXX this looks a potential recursive issue // XXX this looks a potential recursive issue
//connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage())); //connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
if (UASManager::instance()->getActiveUAS()) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &HSIDisplay::_activeVehicleChanged);
{
setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
}
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
this, SLOT(setActiveUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
this, SLOT(setActiveUAS(UASInterface*)));
setFocusPolicy(Qt::StrongFocus); setFocusPolicy(Qt::StrongFocus);
} }
...@@ -918,7 +912,7 @@ void HSIDisplay::setMetricWidth(double width) ...@@ -918,7 +912,7 @@ void HSIDisplay::setMetricWidth(double width)
* *
* @param uas the UAS/MAV to monitor/display with the HUD * @param uas the UAS/MAV to monitor/display with the HUD
*/ */
void HSIDisplay::setActiveUAS(UASInterface* uas) void HSIDisplay::_activeVehicleChanged(Vehicle* vehicle)
{ {
if (this->uas != NULL) { if (this->uas != NULL) {
disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool))); disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
...@@ -953,9 +947,12 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) ...@@ -953,9 +947,12 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
disconnect(this->uas, &UASInterface::navigationControllerErrorsChanged, disconnect(this->uas, &UASInterface::navigationControllerErrorsChanged,
this, &HSIDisplay::UpdateNavErrors); this, &HSIDisplay::UpdateNavErrors);
} }
this->uas = NULL;
if (uas) if (vehicle)
{ {
this->uas = vehicle->uas();
connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)),
this, SLOT(updateSatellite(int,int,float,float,float,bool))); this, SLOT(updateSatellite(int,int,float,float,float,bool)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)),
...@@ -1019,8 +1016,6 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) ...@@ -1019,8 +1016,6 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
statusClearTimer.stop(); statusClearTimer.stop();
} }
this->uas = uas;
resetMAVState(); resetMAVState();
} }
......
...@@ -42,6 +42,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -42,6 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include "HDDisplay.h" #include "HDDisplay.h"
#include "MG.h" #include "MG.h"
#include "Vehicle.h"
class HSIDisplay : public HDDisplay class HSIDisplay : public HDDisplay
{ {
...@@ -51,7 +52,6 @@ public: ...@@ -51,7 +52,6 @@ public:
~HSIDisplay(); ~HSIDisplay();
public slots: public slots:
void setActiveUAS(UASInterface* uas);
/** @brief Set the width in meters this widget shows from top */ /** @brief Set the width in meters this widget shows from top */
void setMetricWidth(double width); void setMetricWidth(double width);
void updateSatellite(int uasid, int satid, float azimuth, float direction, float snr, bool used); void updateSatellite(int uasid, int satid, float azimuth, float direction, float snr, bool used);
...@@ -422,7 +422,8 @@ protected: ...@@ -422,7 +422,8 @@ protected:
bool userZSetPointSet; ///< User set the Z position already bool userZSetPointSet; ///< User set the Z position already
bool userYawSetPointSet; ///< User set the YAW position already bool userYawSetPointSet; ///< User set the YAW position already
private: private slots:
void _activeVehicleChanged(Vehicle* vehicle);
}; };
#endif // HSIDISPLAY_H #endif // HSIDISPLAY_H
...@@ -40,12 +40,12 @@ This file is part of the QGROUNDCONTROL project ...@@ -40,12 +40,12 @@ This file is part of the QGROUNDCONTROL project
#include <qmath.h> #include <qmath.h>
#include <limits> #include <limits>
#include "UASManager.h"
#include "UAS.h" #include "UAS.h"
#include "HUD.h" #include "HUD.h"
#include "QGC.h" #include "QGC.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
#include "MultiVehicleManager.h"
/** /**
* @warning The HUD widget will not start painting its content automatically * @warning The HUD widget will not start painting its content automatically
...@@ -159,11 +159,11 @@ HUD::HUD(int width, int height, QWidget* parent) ...@@ -159,11 +159,11 @@ HUD::HUD(int width, int height, QWidget* parent)
connect(qgcApp(), &QGCApplication::styleChanged, this, &HUD::styleChanged); connect(qgcApp(), &QGCApplication::styleChanged, this, &HUD::styleChanged);
// Connect with UAS // Connect with UAS
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &HUD::_activeVehicleChanged);
createActions(); createActions();
if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS()); _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
} }
HUD::~HUD() HUD::~HUD()
...@@ -265,7 +265,7 @@ void HUD::createActions() ...@@ -265,7 +265,7 @@ void HUD::createActions()
* *
* @param uas the UAS/MAV to monitor/display with the HUD * @param uas the UAS/MAV to monitor/display with the HUD
*/ */
void HUD::setActiveUAS(UASInterface* uas) void HUD::_activeVehicleChanged(Vehicle* vehicle)
{ {
if (this->uas != NULL) { if (this->uas != NULL) {
// Disconnect any previously connected active MAV // Disconnect any previously connected active MAV
...@@ -288,7 +288,10 @@ void HUD::setActiveUAS(UASInterface* uas) ...@@ -288,7 +288,10 @@ void HUD::setActiveUAS(UASInterface* uas)
} }
} }
if (uas) { this->uas = NULL;
if (vehicle) {
this->uas = vehicle->uas();
// Now connect the new UAS // Now connect the new UAS
// Setup communication // Setup communication
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
...@@ -310,8 +313,6 @@ void HUD::setActiveUAS(UASInterface* uas) ...@@ -310,8 +313,6 @@ void HUD::setActiveUAS(UASInterface* uas)
} }
} }
// Set new UAS
this->uas = uas;
} }
//void HUD::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec) //void HUD::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec)
......
...@@ -39,8 +39,10 @@ This file is part of the QGROUNDCONTROL project ...@@ -39,8 +39,10 @@ This file is part of the QGROUNDCONTROL project
#include <QFontDatabase> #include <QFontDatabase>
#include <QTimer> #include <QTimer>
#include <QVector3D> #include <QVector3D>
#include "UASInterface.h" #include "UASInterface.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "Vehicle.h"
/** /**
* @brief Displays a Head Up Display (HUD) * @brief Displays a Head Up Display (HUD)
...@@ -62,9 +64,6 @@ public: ...@@ -62,9 +64,6 @@ public:
public slots: public slots:
void styleChanged(bool styleIsDark); void styleChanged(bool styleIsDark);
/** @brief Set the currently monitored UAS */
virtual void setActiveUAS(UASInterface* uas);
/** @brief Attitude from main autopilot / system state */ /** @brief Attitude from main autopilot / system state */
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
/** @brief Attitude from one specific component / redundant autopilot */ /** @brief Attitude from one specific component / redundant autopilot */
...@@ -98,6 +97,7 @@ public slots: ...@@ -98,6 +97,7 @@ public slots:
protected slots: protected slots:
void _activeVehicleChanged(Vehicle* vehicle);
void paintRollPitchStrips(); void paintRollPitchStrips();
void paintPitchLines(float pitch, QPainter* painter); void paintPitchLines(float pitch, QPainter* painter);
/** @brief Paint text on top of the image and OpenGL drawings */ /** @brief Paint text on top of the image and OpenGL drawings */
......
#include "JoystickAxis.h" #include "JoystickAxis.h"
#include "JoystickInput.h" #include "JoystickInput.h"
#include "ui_JoystickAxis.h" #include "ui_JoystickAxis.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
#include <QString> #include <QString>
JoystickAxis::JoystickAxis(int id, QWidget *parent) : JoystickAxis::JoystickAxis(int id, QWidget *parent) :
...@@ -38,7 +38,7 @@ void JoystickAxis::setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING newMapping) ...@@ -38,7 +38,7 @@ void JoystickAxis::setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING newMapping)
{ {
ui->rangeCheckBox->hide(); ui->rangeCheckBox->hide();
} }
this->setActiveUAS(UASManager::instance()->getActiveUAS()); this->activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
} }
void JoystickAxis::setInverted(bool newValue) void JoystickAxis::setInverted(bool newValue)
...@@ -55,7 +55,7 @@ void JoystickAxis::mappingComboBoxChanged(int newMapping) ...@@ -55,7 +55,7 @@ void JoystickAxis::mappingComboBoxChanged(int newMapping)
{ {
JoystickInput::JOYSTICK_INPUT_MAPPING mapping = (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping; JoystickInput::JOYSTICK_INPUT_MAPPING mapping = (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping;
emit mappingChanged(id, mapping); emit mappingChanged(id, mapping);
updateUIBasedOnUAS(UASManager::instance()->getActiveUAS(), mapping); updateUIBasedOnUAS(MultiVehicleManager::instance()->activeVehicle(), mapping);
} }
void JoystickAxis::inversionCheckBoxChanged(bool inverted) void JoystickAxis::inversionCheckBoxChanged(bool inverted)
...@@ -68,13 +68,19 @@ void JoystickAxis::rangeCheckBoxChanged(bool limited) ...@@ -68,13 +68,19 @@ void JoystickAxis::rangeCheckBoxChanged(bool limited)
emit rangeChanged(id, limited); emit rangeChanged(id, limited);
} }
void JoystickAxis::setActiveUAS(UASInterface* uas) void JoystickAxis::activeVehicleChanged(Vehicle* vehicle)
{ {
updateUIBasedOnUAS(uas, (JoystickInput::JOYSTICK_INPUT_MAPPING)ui->comboBox->currentIndex()); updateUIBasedOnUAS(vehicle, (JoystickInput::JOYSTICK_INPUT_MAPPING)ui->comboBox->currentIndex());
} }
void JoystickAxis::updateUIBasedOnUAS(UASInterface* uas, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping) void JoystickAxis::updateUIBasedOnUAS(Vehicle* vehicle, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping)
{ {
UAS* uas = NULL;
if (vehicle) {
uas = vehicle->uas();
}
// Set the throttle display to only positive if: // Set the throttle display to only positive if:
// * This is the throttle axis AND // * This is the throttle axis AND
// * The current UAS can't reverse OR there is no current UAS // * The current UAS can't reverse OR there is no current UAS
......
...@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project
#include <QWidget> #include <QWidget>
#include "JoystickInput.h" #include "JoystickInput.h"
#include "Vehicle.h"
namespace Ui { namespace Ui {
class JoystickAxis; class JoystickAxis;
...@@ -62,7 +63,7 @@ public slots: ...@@ -62,7 +63,7 @@ public slots:
*/ */
void setValue(float value); void setValue(float value);
/** @brief Specify the UAS that this axis should track for displaying throttle properly. */ /** @brief Specify the UAS that this axis should track for displaying throttle properly. */
void setActiveUAS(UASInterface* uas); void activeVehicleChanged(Vehicle* vehicle);
private: private:
int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput. int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput.
...@@ -72,7 +73,7 @@ private: ...@@ -72,7 +73,7 @@ private:
* @param uas The currently-active UAS. * @param uas The currently-active UAS.
* @param axisMapping The new mapping for this axis. * @param axisMapping The new mapping for this axis.
*/ */
void updateUIBasedOnUAS(UASInterface* uas, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping); void updateUIBasedOnUAS(Vehicle* vehicle, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping);
private slots: private slots:
/** @brief Handle changes to the mapping dropdown bar. */ /** @brief Handle changes to the mapping dropdown bar. */
......
#include "JoystickButton.h" #include "JoystickButton.h"
#include "ui_JoystickButton.h" #include "ui_JoystickButton.h"
#include "UASManager.h" #include "MultiVehicleManager.h"
JoystickButton::JoystickButton(int id, QWidget *parent) : JoystickButton::JoystickButton(int id, QWidget *parent) :
QWidget(parent), QWidget(parent),
...@@ -9,7 +9,7 @@ JoystickButton::JoystickButton(int id, QWidget *parent) : ...@@ -9,7 +9,7 @@ JoystickButton::JoystickButton(int id, QWidget *parent) :
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
m_ui->joystickButtonLabel->setText(QString::number(id)); m_ui->joystickButtonLabel->setText(QString::number(id));
this->setActiveUAS(UASManager::instance()->getActiveUAS()); this->activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int)));
} }
...@@ -18,12 +18,14 @@ JoystickButton::~JoystickButton() ...@@ -18,12 +18,14 @@ JoystickButton::~JoystickButton()
delete m_ui; delete m_ui;
} }
void JoystickButton::setActiveUAS(UASInterface* uas) void JoystickButton::activeVehicleChanged(Vehicle* vehicle)
{ {
// Disable signals so that changes to joystickAction don't trigger JoystickInput updates. // Disable signals so that changes to joystickAction don't trigger JoystickInput updates.
disconnect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); disconnect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int)));
if (uas) if (vehicle)
{ {
UAS* uas = vehicle->uas();
m_ui->joystickAction->setEnabled(true); m_ui->joystickAction->setEnabled(true);
m_ui->joystickAction->clear(); m_ui->joystickAction->clear();
m_ui->joystickAction->addItem("--"); m_ui->joystickAction->addItem("--");
......
...@@ -30,7 +30,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -30,7 +30,7 @@ This file is part of the QGROUNDCONTROL project
#include <QWidget> #include <QWidget>
#include "UASInterface.h" #include "Vehicle.h"
namespace Ui namespace Ui
{ {
...@@ -47,7 +47,7 @@ public: ...@@ -47,7 +47,7 @@ public:
public slots: public slots:
/** @brief Specify the UAS that this axis should track for displaying throttle properly. */ /** @brief Specify the UAS that this axis should track for displaying throttle properly. */
void setActiveUAS(UASInterface* uas); void activeVehicleChanged(Vehicle* vehicle);
/** @brieft Specify which action this button should correspond to. /** @brieft Specify which action this button should correspond to.
* Values 0 and higher indicate a specific action, while -1 indicates no action. */ * Values 0 and higher indicate a specific action, while -1 indicates no action. */
void setAction(int index); void setAction(int index);
......
...@@ -187,7 +187,7 @@ void JoystickWidget::createUIForJoystick() ...@@ -187,7 +187,7 @@ void JoystickWidget::createUIForJoystick()
JoystickButton* button = new JoystickButton(i, m_ui->buttonBox); JoystickButton* button = new JoystickButton(i, m_ui->buttonBox);
button->setAction(joystick->getActionForButton(i)); button->setAction(joystick->getActionForButton(i));
connect(button, SIGNAL(actionChanged(int,int)), this->joystick, SLOT(setButtonAction(int,int))); connect(button, SIGNAL(actionChanged(int,int)), this->joystick, SLOT(setButtonAction(int,int)));
connect(this->joystick, SIGNAL(activeUASSet(UASInterface*)), button, SLOT(setActiveUAS(UASInterface*))); connect(this->joystick, &JoystickInput::activeVehicleChanged, button, &JoystickButton::activeVehicleChanged);
m_ui->buttonLayout->addWidget(button); m_ui->buttonLayout->addWidget(button);
buttons.append(button); buttons.append(button);
} }
...@@ -230,7 +230,7 @@ void JoystickWidget::createUIForJoystick() ...@@ -230,7 +230,7 @@ void JoystickWidget::createUIForJoystick()
connect(axis, SIGNAL(mappingChanged(int,JoystickInput::JOYSTICK_INPUT_MAPPING)), this->joystick, SLOT(setAxisMapping(int,JoystickInput::JOYSTICK_INPUT_MAPPING))); connect(axis, SIGNAL(mappingChanged(int,JoystickInput::JOYSTICK_INPUT_MAPPING)), this->joystick, SLOT(setAxisMapping(int,JoystickInput::JOYSTICK_INPUT_MAPPING)));
connect(axis, SIGNAL(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool))); connect(axis, SIGNAL(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool)));
connect(axis, SIGNAL(rangeChanged(int,bool)), this->joystick, SLOT(setAxisRangeLimit(int,bool))); connect(axis, SIGNAL(rangeChanged(int,bool)), this->joystick, SLOT(setAxisRangeLimit(int,bool)));
connect(this->joystick, SIGNAL(activeUASSet(UASInterface*)), axis, SLOT(setActiveUAS(UASInterface*))); connect(this->joystick, &JoystickInput::activeVehicleChanged, axis, &JoystickAxis::activeVehicleChanged);
m_ui->axesLayout->addWidget(axis); m_ui->axesLayout->addWidget(axis);
axes.append(axis); axes.append(axis);
} }
......
...@@ -71,6 +71,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -71,6 +71,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "QGCDockWidget.h" #include "QGCDockWidget.h"
#include "MultiVehicleManager.h"
#include "CustomCommandWidget.h" #include "CustomCommandWidget.h"
#ifdef UNITTEST_BUILD #ifdef UNITTEST_BUILD
...@@ -569,13 +570,13 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) ...@@ -569,13 +570,13 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName)
#ifndef __mobile__ #ifndef __mobile__
void MainWindow::_showHILConfigurationWidgets(void) void MainWindow::_showHILConfigurationWidgets(void)
{ {
UASInterface* uas = UASManager::instance()->getActiveUAS(); Vehicle* vehicle = MultiVehicleManager::instance()->activeVehicle();
if (!uas) { if (!vehicle) {
return; return;
} }
UAS* mav = dynamic_cast<UAS*>(uas); UAS* mav = vehicle->uas();
Q_ASSERT(mav); Q_ASSERT(mav);
int uasId = mav->getUASID(); int uasId = mav->getUASID();
...@@ -757,26 +758,12 @@ void MainWindow::connectCommonActions() ...@@ -757,26 +758,12 @@ void MainWindow::connectCommonActions()
_ui.actionSetup->activate(QAction::Trigger); _ui.actionSetup->activate(QAction::Trigger);
} }
// The UAS actions are not enabled without connection to system
_ui.actionLiftoff->setEnabled(false);
_ui.actionLand->setEnabled(false);
_ui.actionEmergency_Kill->setEnabled(false);
_ui.actionEmergency_Land->setEnabled(false);
_ui.actionShutdownMAV->setEnabled(false);
// Connect actions from ui // Connect actions from ui
connect(_ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(manageLinks())); connect(_ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(manageLinks()));
// Connect internal actions // Connect internal actions
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(UASCreated(UASInterface*))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &MainWindow::_vehicleAdded);
connect(UASManager::instance(), SIGNAL(UASDeleted(int)), this, SLOT(UASDeleted(int))); connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MainWindow::_vehicleRemoved);
// Unmanned System controls
connect(_ui.actionLiftoff, SIGNAL(triggered()), UASManager::instance(), SLOT(launchActiveUAS()));
connect(_ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS()));
connect(_ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS()));
connect(_ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS()));
connect(_ui.actionShutdownMAV, SIGNAL(triggered()), UASManager::instance(), SLOT(shutdownActiveUAS()));
// Views actions // Views actions
connect(_ui.actionFlight, SIGNAL(triggered()), this, SLOT(loadFlightView())); connect(_ui.actionFlight, SIGNAL(triggered()), this, SLOT(loadFlightView()));
...@@ -853,17 +840,9 @@ void MainWindow::commsWidgetDestroyed(QObject *obj) ...@@ -853,17 +840,9 @@ void MainWindow::commsWidgetDestroyed(QObject *obj)
} }
} }
void MainWindow::UASCreated(UASInterface* uas) void MainWindow::_vehicleAdded(Vehicle* vehicle)
{ {
// The UAS actions are not enabled without connection to system connect(vehicle->uas(), SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)));
_ui.actionLiftoff->setEnabled(true);
_ui.actionLand->setEnabled(true);
_ui.actionEmergency_Kill->setEnabled(true);
_ui.actionEmergency_Land->setEnabled(true);
_ui.actionShutdownMAV->setEnabled(true);
connect(uas, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)));
connect(uas, SIGNAL(misconfigurationDetected(UASInterface*)), this, SLOT(handleMisconfiguration(UASInterface*)));
// HIL // HIL
#ifndef __mobile__ #ifndef __mobile__
...@@ -883,11 +862,13 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -883,11 +862,13 @@ void MainWindow::UASCreated(UASInterface* uas)
} }
} }
void MainWindow::UASDeleted(int uasId) void MainWindow::_vehicleRemoved(Vehicle* vehicle)
{ {
if (_mapUasId2HilDockWidget.contains(uasId)) { int vehicleId = vehicle->id();
_mapUasId2HilDockWidget[uasId]->deleteLater();
_mapUasId2HilDockWidget.remove(uasId); if (_mapUasId2HilDockWidget.contains(vehicleId)) {
_mapUasId2HilDockWidget[vehicleId]->deleteLater();
_mapUasId2HilDockWidget.remove(vehicleId);
} }
} }
...@@ -1029,33 +1010,6 @@ void MainWindow::_showDockWidgetAction(bool show) ...@@ -1029,33 +1010,6 @@ void MainWindow::_showDockWidgetAction(bool show)
} }
void MainWindow::handleMisconfiguration(UASInterface* uas)
{
static QTime lastTime;
// We have to debounce this signal
if (!lastTime.isValid()) {
lastTime.start();
} else {
if (lastTime.elapsed() < 10000) {
lastTime.start();
return;
}
}
// Ask user if they want to handle this now
QMessageBox::StandardButton button =
QGCMessageBox::question(
tr("Missing or Invalid Onboard Configuration"),
tr("The onboard system configuration is missing or incomplete. Do you want to resolve this now?"),
QMessageBox::Ok | QMessageBox::Cancel,
QMessageBox::Ok);
if (button == QMessageBox::Ok) {
// They want to handle it, make sure this system is selected
UASManager::instance()->setActiveUAS(uas);
// Flick to config view
loadSetupView();
}
}
void MainWindow::loadAnalyzeView() void MainWindow::loadAnalyzeView()
{ {
if (_currentView != VIEW_ANALYZE) if (_currentView != VIEW_ANALYZE)
......
...@@ -65,6 +65,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -65,6 +65,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCMAVLinkLogPlayer.h" #include "QGCMAVLinkLogPlayer.h"
#include "MAVLinkDecoder.h" #include "MAVLinkDecoder.h"
#include "QGCUASFileViewMulti.h" #include "QGCUASFileViewMulti.h"
#include "Vehicle.h"
class QGCMapTool; class QGCMapTool;
class QGCMAVLinkMessageSender; class QGCMAVLinkMessageSender;
...@@ -134,13 +135,6 @@ public slots: ...@@ -134,13 +135,6 @@ public slots:
/** @brief Show the application settings */ /** @brief Show the application settings */
void showSettings(); void showSettings();
/** @brief Add a new UAS */
void UASCreated(UASInterface* uas);
/** @brief Remove an old UAS */
void UASDeleted(int uasID);
void handleMisconfiguration(UASInterface* uas);
/** @brief Load configuration views */ /** @brief Load configuration views */
void loadSetupView(); void loadSetupView();
/** @brief Load view for pilot */ /** @brief Load view for pilot */
...@@ -288,6 +282,10 @@ private slots: ...@@ -288,6 +282,10 @@ private slots:
void _showQmlTestWidget(void); void _showQmlTestWidget(void);
#endif #endif
void _closeWindow(void) { close(); } void _closeWindow(void) { close(); }
private slots:
void _vehicleAdded(Vehicle* vehicle);
void _vehicleRemoved(Vehicle* vehicle);
private: private:
/// Constructor is private since all creation should be through MainWindow::_create /// Constructor is private since all creation should be through MainWindow::_create
......
...@@ -117,52 +117,6 @@ ...@@ -117,52 +117,6 @@
<string>Ctrl+Q</string> <string>Ctrl+Q</string>
</property> </property>
</action> </action>
<action name="actionLiftoff">
<property name="enabled">
<bool>true</bool>
</property>
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/res/Launch</normaloff>
<normalon>:/res/Launch</normalon>:/res/Launch</iconset>
</property>
<property name="text">
<string>Liftoff</string>
</property>
</action>
<action name="actionLand">
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/res/Land</normaloff>:/res/Land</iconset>
</property>
<property name="text">
<string>Land</string>
</property>
</action>
<action name="actionEmergency_Land">
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/res/Kill</normaloff>:/res/Kill</iconset>
</property>
<property name="text">
<string>Emergency Land</string>
</property>
<property name="shortcut">
<string>Ctrl+L</string>
</property>
</action>
<action name="actionEmergency_Kill">
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/res/Kill</normaloff>:/res/Kill</iconset>
</property>
<property name="text">
<string>Kill UAS</string>
</property>
<property name="shortcut">
<string>Ctrl+K</string>
</property>
</action>
<action name="actionAdd_Link"> <action name="actionAdd_Link">
<property name="text"> <property name="text">
<string>Manage Communication Links</string> <string>Manage Communication Links</string>
...@@ -215,21 +169,6 @@ ...@@ -215,21 +169,6 @@
<string>Mute Audio Output</string> <string>Mute Audio Output</string>
</property> </property>
</action> </action>
<action name="actionShutdownMAV">
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/res/Shutdown</normaloff>:/res/Shutdown</iconset>
</property>
<property name="text">
<string>Shutdown MAV</string>
</property>
<property name="toolTip">
<string>Shutdown the onboard computer - works not during flight</string>
</property>
<property name="statusTip">
<string>Shutdown the onboard computer - works not during flight</string>
</property>
</action>
<action name="actionSettings"> <action name="actionSettings">
<property name="text"> <property name="text">
<string>Settings</string> <string>Settings</string>
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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