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 += \
src/QmlControls/ParameterEditorController.h \
src/QmlControls/ScreenToolsController.h \
src/SerialPortIds.h \
src/uas/QGCMAVLinkUASFactory.h \
src/uas/FileManager.h \
src/uas/UAS.h \
src/uas/UASInterface.h \
......@@ -394,7 +393,6 @@ SOURCES += \
src/QmlControls/MavManager.cc \
src/QmlControls/ParameterEditorController.cc \
src/QmlControls/ScreenToolsController.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/uas/FileManager.cc \
src/uas/UAS.cc \
src/uas/UASManager.cc \
......@@ -559,15 +557,12 @@ SOURCES += \
#
INCLUDEPATH += \
src/AutoPilotPlugins/PX4 \
src/FirmwarePlugin \
src/Vehicle \
src/VehicleSetup \
src/AutoPilotPlugins/PX4 \
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/AutoPilotPluginManager.h \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h \
......@@ -587,6 +582,12 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/SafetyComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponent.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/VehicleComponent.h \
......@@ -600,9 +601,6 @@ HEADERS += \
}
SOURCES += \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/AutoPilotPlugins/AutoPilotPlugin.cc \
src/AutoPilotPlugins/AutoPilotPluginManager.cc \
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc \
......@@ -622,6 +620,11 @@ SOURCES += \
src/AutoPilotPlugins/PX4/SafetyComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.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/VehicleComponent.cc \
......
......@@ -30,16 +30,16 @@
#include "MainWindow.h"
#include "ParameterLoader.h"
AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) :
AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
QObject(parent),
_uas(uas),
_vehicle(vehicle),
_pluginReady(false),
_setupComplete(false)
{
Q_ASSERT(_uas);
Q_ASSERT(vehicle);
connect(_uas, &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(_uas, &UASInterface::armingChanged, this, &AutoPilotPlugin::armedChanged);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(_vehicle->uas(), &UASInterface::armingChanged, this, &AutoPilotPlugin::armedChanged);
connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged);
}
......@@ -102,8 +102,8 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
mavlink_message_t msg;
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);
_uas->sendMessage(msg);
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);
_vehicle->sendMessage(msg);
}
void AutoPilotPlugin::refreshAllParameters(void)
......@@ -169,7 +169,7 @@ const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_getParameterLoader()->writeParametersToStream(stream, _uas->getUASName());
_getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName());
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
......@@ -179,5 +179,5 @@ QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
bool AutoPilotPlugin::armed(void)
{
return _uas->isArmed();
return _vehicle->uas()->isArmed();
}
......@@ -32,11 +32,12 @@
#include <QString>
#include <QQmlContext>
#include "UASInterface.h"
#include "VehicleComponent.h"
#include "FactSystem.h"
#include "Vehicle.h"
class ParameterLoader;
class Vehicle;
/// This is the base class for AutoPilot plugins
///
......@@ -50,7 +51,7 @@ class AutoPilotPlugin : public QObject
Q_OBJECT
public:
AutoPilotPlugin(UASInterface* uas, QObject* parent);
AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin();
/// true: plugin is ready for use, plugin should no longer be used
......@@ -119,7 +120,7 @@ public:
bool setupComplete(void);
bool armed(void);
UASInterface* uas(void) { return _uas; }
Vehicle* vehicle(void) { return _vehicle; }
signals:
void pluginReadyChanged(bool pluginReady);
......@@ -134,9 +135,9 @@ protected:
/// Returns the ParameterLoader
virtual ParameterLoader* _getParameterLoader(void) = 0;
UASInterface* _uas;
bool _pluginReady;
bool _setupComplete;
Vehicle* _vehicle;
bool _pluginReady;
bool _setupComplete;
private slots:
void _uasDisconnected(void);
......
......@@ -27,98 +27,26 @@
#include "AutoPilotPluginManager.h"
#include "PX4/PX4AutoPilotPlugin.h"
#include "Generic/GenericAutoPilotPlugin.h"
#include "QGCApplication.h"
#include "QGCMessageBox.h"
#include "UASManager.h"
IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager)
AutoPilotPluginManager::AutoPilotPluginManager(QObject* 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()
{
#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();
GenericAutoPilotPlugin::clearStaticData();
}
/// Create the plugin for this uas
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)
AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle)
{
Q_ASSERT(uas);
MAV_AUTOPILOT autopilotType = _installedAutopilotType(static_cast<MAV_AUTOPILOT>(uas->getAutopilotType()));
int uasId = uas->getUASID();
Q_ASSERT(uasId != 0);
if (_pluginMap.contains(autopilotType) && _pluginMap[autopilotType].contains(uasId)) {
_pluginMap[autopilotType][uasId].clear();
_pluginMap[autopilotType].remove(uasId);
if (vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
return new PX4AutoPilotPlugin(vehicle, vehicle);
} else {
return new GenericAutoPilotPlugin(vehicle, vehicle);
}
}
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 @@
#include <QList>
#include <QString>
#include "UASInterface.h"
#include "VehicleComponent.h"
#include "AutoPilotPlugin.h"
#include "QGCSingleton.h"
#include "QGCMAVLink.h"
#include "Vehicle.h"
/// AutoPilotPlugin manager is a singleton which maintains the list of AutoPilotPlugin objects.
......@@ -47,23 +44,12 @@ class AutoPilotPluginManager : public QGCSingleton
DECLARE_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager)
public:
/// Returns the singleton AutoPilotPlugin instance for the specified uas. Returned as QSharedPointer
/// 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);
AutoPilotPlugin* newAutopilotPluginForVehicle(Vehicle* vehicle);
private:
/// All access to singleton is through AutoPilotPluginManager::instance
AutoPilotPluginManager(QObject* parent = NULL);
~AutoPilotPluginManager();
MAV_AUTOPILOT _installedAutopilotType(MAV_AUTOPILOT autopilot);
QMap<MAV_AUTOPILOT, QMap<int, QSharedPointer<AutoPilotPlugin> > > _pluginMap; ///< Map of AutoPilot plugins _pluginMap[MAV_TYPE][UASid]
};
#endif
......@@ -26,12 +26,12 @@
#include "GenericAutoPilotPlugin.h"
GenericAutoPilotPlugin::GenericAutoPilotPlugin(UASInterface* uas, QObject* parent) :
AutoPilotPlugin(uas, parent)
GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* 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);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReady);
......
......@@ -25,7 +25,6 @@
#define GENERICAUTOPILOT_H
#include "AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "GenericParameterFacts.h"
/// @file
......@@ -38,7 +37,7 @@ class GenericAutoPilotPlugin : public AutoPilotPlugin
Q_OBJECT
public:
GenericAutoPilotPlugin(UASInterface* uas, QObject* parent = NULL);
GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent = NULL);
// Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void);
......
......@@ -28,8 +28,8 @@
#include <QDebug>
GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) :
ParameterLoader(autopilot, uas, parent)
GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, vehicle, parent)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
}
......@@ -41,7 +41,7 @@ class GenericParameterFacts : public ParameterLoader
public:
/// @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
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
......
......@@ -27,7 +27,7 @@
#include "AirframeComponentController.h"
#include "AirframeComponentAirframes.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
#include "MultiVehicleManager.h"
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include "QGCMessageBox.h"
......@@ -98,7 +98,7 @@ AirframeComponentController::~AirframeComponentController()
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.");
return;
}
......
......@@ -26,7 +26,6 @@
#include "FlightModesComponentController.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h"
#include <QVariant>
......
......@@ -23,7 +23,6 @@
#include "PX4AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h"
#include "FlightModesComponentController.h"
......@@ -64,8 +63,8 @@ union px4_custom_mode {
float data_float;
};
PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
AutoPilotPlugin(uas, parent),
PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent),
_parameterFacts(NULL),
_airframeComponent(NULL),
_radioComponent(NULL),
......@@ -75,15 +74,15 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
_powerComponent(NULL),
_incorrectParameterVersion(false)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
_parameterFacts = new PX4ParameterLoader(this, uas, this);
_parameterFacts = new PX4ParameterLoader(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_pluginReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress);
_airframeFacts = new PX4AirframeLoader(this, uas, this);
_airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
Q_CHECK_PTR(_airframeFacts);
PX4ParameterLoader::loadParameterFactMetaData();
......@@ -105,7 +104,7 @@ void PX4AutoPilotPlugin::clearStaticData(void)
const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
{
if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_uas);
Q_ASSERT(_vehicle);
if (pluginReady()) {
bool noRCTransmitter = false;
......@@ -114,34 +113,34 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
noRCTransmitter = rcFact->value().toInt() == 1;
}
_airframeComponent = new AirframeComponent(_uas, this);
_airframeComponent = new AirframeComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
if (!noRCTransmitter) {
_radioComponent = new RadioComponent(_uas, this);
_radioComponent = new RadioComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
_flightModesComponent = new FlightModesComponent(_uas, this);
_flightModesComponent = new FlightModesComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_flightModesComponent);
_flightModesComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
}
_sensorsComponent = new SensorsComponent(_uas, this);
_sensorsComponent = new SensorsComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_sensorsComponent);
_sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
_powerComponent = new PowerComponent(_uas, this);
_powerComponent = new PowerComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_powerComponent);
_powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
_safetyComponent = new SafetyComponent(_uas, this);
_safetyComponent = new SafetyComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_safetyComponent);
_safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
......
......@@ -25,8 +25,6 @@
#define PX4AUTOPILOT_H
#include "AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "UASInterface.h"
#include "PX4ParameterLoader.h"
#include "PX4AirframeLoader.h"
#include "AirframeComponent.h"
......@@ -35,6 +33,7 @@
#include "SensorsComponent.h"
#include "SafetyComponent.h"
#include "PowerComponent.h"
#include "Vehicle.h"
#include <QImage>
......@@ -47,7 +46,7 @@ class PX4AutoPilotPlugin : public AutoPilotPlugin
Q_OBJECT
public:
PX4AutoPilotPlugin(UASInterface* uas, QObject* parent);
PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~PX4AutoPilotPlugin();
// Overrides from AutoPilotPlugin
......
......@@ -38,10 +38,10 @@ QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog")
bool PX4ParameterLoader::_parameterMetaDataLoaded = false;
QMap<QString, FactMetaData*> PX4ParameterLoader::_mapParameterName2FactMetaData;
PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) :
ParameterLoader(autopilot, uas, parent)
PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, vehicle, parent)
{
Q_ASSERT(uas);
Q_ASSERT(vehicle);
}
/// Converts a string to a typed QVariant
......
......@@ -31,8 +31,8 @@
#include "ParameterLoader.h"
#include "FactSystem.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
......@@ -47,7 +47,7 @@ class PX4ParameterLoader : public ParameterLoader
public:
/// @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
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
......
......@@ -26,7 +26,6 @@
#include "PowerComponentController.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
#include <QVariant>
......@@ -71,7 +70,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int
Q_UNUSED(compId);
Q_UNUSED(severity);
UASInterface* uas = _autopilot->uas();
UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
return;
......
......@@ -26,7 +26,6 @@
/// @author Don Gagne <don@thegagnes.com
#include "RadioComponentController.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
#include "AutoPilotPluginManager.h"
......
......@@ -26,7 +26,6 @@
#include "SensorsComponentController.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
#include <QVariant>
......@@ -208,7 +207,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
Q_UNUSED(compId);
Q_UNUSED(severity);
UASInterface* uas = _autopilot->uas();
UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
return;
......@@ -427,7 +426,7 @@ void SensorsComponentController::_refreshParams(void)
bool SensorsComponentController::fixedWing(void)
{
UASInterface* uas = _autopilot->uas();
UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas);
return uas->getSystemType() == MAV_TYPE_FIXED_WING ||
uas->getSystemType() == MAV_TYPE_VTOL_DUOROTOR ||
......
......@@ -22,8 +22,7 @@
======================================================================*/
#include "FactPanelController.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h"
#include "MultiVehicleManager.h"
#include "QGCMessageBox.h"
#include <QQmlEngine>
......@@ -34,15 +33,15 @@
QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog")
FactPanelController::FactPanelController(void) :
_autopilot(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);
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas);
_autopilot = _vehicle->autopilotPlugin();
Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->pluginReady());
......
......@@ -32,7 +32,6 @@
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
#include "UASManagerInterface.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(FactPanelControllerLog)
......@@ -62,8 +61,9 @@ protected:
/// Report a missing parameter to the FactPanel Qml element
void _reportMissingParameter(int componentId, const QString& name);
UASInterface* _uas;
QSharedPointer<AutoPilotPlugin> _autopilot;
Vehicle* _vehicle;
UASInterface* _uas;
AutoPilotPlugin* _autopilot;
private slots:
void _checkForMissingFactPanel(void);
......
......@@ -25,8 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "FactSystem.h"
#include "UASManager.h"
#include "QGCApplication.h"
#include "FactPanelController.h"
#include <QtQml>
......
......@@ -27,8 +27,7 @@
#include "FactSystemTestBase.h"
#include "LinkManager.h"
#include "MockLink.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "MultiVehicleManager.h"
#include "QGCApplication.h"
#include "QGCMessageBox.h"
#include "QGCQuickWidget.h"
......@@ -45,45 +44,20 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
{
UnitTest::init();
LinkManager* _linkMgr = LinkManager::instance();
MockLink* link = new MockLink();
link->setAutopilotType(autopilot);
_linkMgr->_addLink(link);