Skip to content

Commit

Permalink
Convert MultiVehicleManager to Singleton
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Nov 29, 2024
1 parent 6bbb5e7 commit 4508bb3
Show file tree
Hide file tree
Showing 63 changed files with 387 additions and 410 deletions.
7 changes: 3 additions & 4 deletions src/AnalyzeView/LogDownloadController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,9 @@ LogDownloadController::LogDownloadController(void)
, _retries(0)
, _apmOneBased(0)
{
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
connect(&_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload);
_setActiveVehicle(manager->activeVehicle());
_setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
}

//----------------------------------------------------------------------------------------
Expand Down Expand Up @@ -600,7 +599,7 @@ LogDownloadController::eraseAll(void)
MAVLinkProtocol::getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId());
MultiVehicleManager::instance()->activeVehicle()->id(), MultiVehicleManager::instance()->activeVehicle()->defaultComponentId());
_vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
}
refresh();
Expand Down
5 changes: 2 additions & 3 deletions src/AnalyzeView/MAVLinkConsoleController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,9 @@ MAVLinkConsoleController::MAVLinkConsoleController(QObject *parent)
{
// qCDebug(MAVLinkConsoleControllerLog) << Q_FUNC_INFO << this;

MultiVehicleManager *const manager = qgcApp()->toolbox()->multiVehicleManager();
(void) connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle);
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle);

_setActiveVehicle(manager->activeVehicle());
_setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
}

MAVLinkConsoleController::~MAVLinkConsoleController()
Expand Down
12 changes: 4 additions & 8 deletions src/AnalyzeView/MAVLinkInspectorController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,9 @@ QGC_LOGGING_CATEGORY(MAVLinkInspectorControllerLog, "qgc.analyzeview.mavlinkinsp
//-----------------------------------------------------------------------------
MAVLinkInspectorController::MAVLinkInspectorController()
{
MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager();
connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded);
connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
_updateFrequencyTimer.start(1000);
Expand Down Expand Up @@ -256,13 +255,10 @@ void MAVLinkInspectorController::setMessageInterval(int32_t rate)
{
if(!_activeSystem) return;

MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager();
if(!multiVehicleManager) return;

const uint8_t sysId = _selectedSystemID();
if(sysId == 0) return;

Vehicle* vehicle = multiVehicleManager->getVehicleById(sysId);
Vehicle* vehicle = MultiVehicleManager::instance()->getVehicleById(sysId);
if(!vehicle) return;

QGCMAVLinkMessage* msg = _activeSystem->selectedMsg();
Expand Down
2 changes: 1 addition & 1 deletion src/AutoPilotPlugins/PX4/AirframeComponentController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ AirframeComponentController::~AirframeComponentController()

void AirframeComponentController::changeAutostart(void)
{
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) {
if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
qgcApp()->showAppMessage(tr("You cannot change airframe configuration while connected to multiple vehicles."));
return;
}
Expand Down
4 changes: 2 additions & 2 deletions src/Camera/QGCCameraManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)

_addCameraControlToLists(_simulatedCameraControl);

connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
connect(&_camerasLostHeartbeatTimer, &QTimer::timeout, this, &QGCCameraManager::_checkForLostCameras);

Expand Down Expand Up @@ -87,7 +87,7 @@ void QGCCameraManager::_vehicleReady(bool ready)
{
qCDebug(CameraManagerLog) << "_vehicleReady(" << ready << ")";
if(ready) {
if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) {
if(MultiVehicleManager::instance()->activeVehicle() == _vehicle) {
_vehicleReadyState = true;
_activeJoystickChanged(JoystickManager::instance()->activeJoystick());
connect(JoystickManager::instance(), &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged);
Expand Down
4 changes: 1 addition & 3 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -237,8 +237,6 @@ void LinkManager::_linkDisconnected()
for (auto it = _rgLinks.begin(); it != _rgLinks.end(); ++it) {
if (it->get() == link) {
qCDebug(LinkManagerLog) << Q_FUNC_INFO << it->get()->linkConfiguration()->name() << it->use_count();
SharedLinkConfigurationPtr config = it->get()->linkConfiguration();
config->setLink(nullptr);
(void) _rgLinks.erase(it);
return;
}
Expand Down Expand Up @@ -511,7 +509,7 @@ void LinkManager::shutdown()
disconnectAll();

// Wait for all the vehicles to go away to ensure an orderly shutdown and deletion of all objects
while (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count()) {
while (MultiVehicleManager::instance()->vehicles()->count()) {
QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/LogReplayLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ LogReplayLink::~LogReplayLink(void)
bool LogReplayLink::_connect(void)
{
// Disallow replay when any links are connected
if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) {
if (MultiVehicleManager::instance()->activeVehicle()) {
emit communicationError(_errorTitle, tr("You must close all connections prior to replaying a log."));
return false;
}
Expand Down
28 changes: 19 additions & 9 deletions src/Comms/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "QGCTemporaryFile.h"
#include "QGCToolbox.h"
#include "SettingsManager.h"
#include "QmlObjectListModel.h"

#include <QtCore/qapplicationstatic.h>
#include <QtCore/QDir>
Expand All @@ -25,19 +26,13 @@

QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "qgc.comms.mavlinkprotocol")

Q_APPLICATION_STATIC(MAVLinkProtocol, _mavlinkProtocol);
Q_APPLICATION_STATIC(MAVLinkProtocol, _mavlinkProtocolInstance);

MAVLinkProtocol::MAVLinkProtocol(QObject *parent)
: QObject(parent)
, _tempLogFile(new QGCTemporaryFile(QStringLiteral("%2.%3").arg(_tempLogFileTemplate, _logFileExtension), this))
{
// qCDebug(MAVLinkProtocolLog) << Q_FUNC_INFO << this;

(void) memset(_firstMessage, 1, sizeof(_firstMessage));

(void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged);

_loadSettings();
}

MAVLinkProtocol::~MAVLinkProtocol()
Expand All @@ -50,7 +45,22 @@ MAVLinkProtocol::~MAVLinkProtocol()

MAVLinkProtocol *MAVLinkProtocol::instance()
{
return _mavlinkProtocol();
return _mavlinkProtocolInstance();
}

void MAVLinkProtocol::init()
{
if (_initialized) {
return;
}

(void) memset(_firstMessage, 1, sizeof(_firstMessage));

(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged);

_loadSettings();

_initialized = true;
}

void MAVLinkProtocol::setVersion(unsigned version)
Expand Down Expand Up @@ -476,7 +486,7 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)

void MAVLinkProtocol::_vehicleCountChanged()
{
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() == 0) {
if (MultiVehicleManager::instance()->vehicles()->count() == 0) {
_stopLogging();
}
}
3 changes: 3 additions & 0 deletions src/Comms/MAVLinkProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ class MAVLinkProtocol : public QObject
/// @return The singleton instance.
static MAVLinkProtocol *instance();

void init();

/// Get the human-friendly name of this protocol
static QString getName() { return QStringLiteral("MAVLink protocol"); }

Expand Down Expand Up @@ -143,6 +145,7 @@ private slots:

int _systemId = kMaxSysId;
unsigned _currentVersion = 100;
bool _initialized = false;

static constexpr const char *_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file
static constexpr const char *_logFileExtension = "mavlink"; ///< Extension for log files
Expand Down
4 changes: 2 additions & 2 deletions src/FactSystem/FactControls/FactPanelController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@ QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog")
FactPanelController::FactPanelController(QObject *parent)
: QObject(parent)
{
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
_vehicle = MultiVehicleManager::instance()->activeVehicle();
if (_vehicle) {
_autopilot = _vehicle->autopilotPlugin();
} else {
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle();
_vehicle = MultiVehicleManager::instance()->offlineEditingVehicle();
}

_missingParametersTimer.setInterval(500);
Expand Down
18 changes: 9 additions & 9 deletions src/FollowMe/FollowMe.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,18 +60,18 @@ void FollowMe::_settingsChanged(QVariant value)

switch (_currentMode) {
case MODE_NEVER:
(void) disconnect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) disconnect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
(void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_disableFollowSend();
break;
case MODE_ALWAYS:
(void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_enableFollowSend();
break;
case MODE_FOLLOWME:
(void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
_enableIfVehicleInFollow();
break;
}
Expand Down Expand Up @@ -106,7 +106,7 @@ void FollowMe::_sendGCSMotionReport()
if (_currentMode == MODE_ALWAYS) {
needFollowMe = true;
} else if (_currentMode == MODE_FOLLOWME) {
QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles();
QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles();
for (int i = 0; i < vehicles->count(); i++) {
const Vehicle* const vehicle = vehicles->value<const Vehicle*>(i);
if (_isFollowFlightMode(vehicle, vehicle->flightMode())) {
Expand Down Expand Up @@ -162,7 +162,7 @@ void FollowMe::_sendGCSMotionReport()
motionReport.vyMetersPerSec = 0;
}

QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles();
QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles();

for (int i = 0; i < vehicles->count(); i++) {
Vehicle* const vehicle = vehicles->value<Vehicle*>(i);
Expand Down Expand Up @@ -192,7 +192,7 @@ void FollowMe::_enableIfVehicleInFollow()
}

// Any vehicle in follow mode will enable the system
QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles();
QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles();

for (int i = 0; i < vehicles->count(); i++) {
const Vehicle* const vehicle = vehicles->value<const Vehicle*>(i);
Expand Down
2 changes: 1 addition & 1 deletion src/GPS/RTCMMavlink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ void RTCMMavlink::RTCMDataUpdate(QByteArrayView data)

void RTCMMavlink::_sendMessageToVehicle(const mavlink_gps_rtcm_data_t &data)
{
QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles();
QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles();
for (qsizetype i = 0; i < vehicles->count(); i++) {
Vehicle* const vehicle = qobject_cast<Vehicle*>(vehicles->get(i));
const SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
Expand Down
15 changes: 7 additions & 8 deletions src/Joystick/Joystick.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,14 +41,13 @@ AssignableButtonAction::AssignableButtonAction(QObject* parent, QString action_,
{
}

Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager)
Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount)
: _name (name)
, _axisCount (axisCount)
, _buttonCount (buttonCount)
, _hatCount (hatCount)
, _hatButtonCount (4 * hatCount)
, _totalButtonCount (_buttonCount+_hatButtonCount)
, _multiVehicleManager (multiVehicleManager)
, _customActionManager (qgcApp()->toolbox()->settingsManager()->customMavlinkActionsSettings()->joystickActionsFile())
{
// qCDebug(JoystickLog) << Q_FUNC_INFO << this;
Expand All @@ -65,11 +64,11 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
_rgButtonValues[i] = BUTTON_UP;
_buttonActionArray.append(nullptr);
}
_buildActionList(_multiVehicleManager->activeVehicle());
_updateTXModeSettingsKey(_multiVehicleManager->activeVehicle());
_buildActionList(MultiVehicleManager::instance()->activeVehicle());
_updateTXModeSettingsKey(MultiVehicleManager::instance()->activeVehicle());
_loadSettings();
connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged);
connect(qgcApp()->toolbox()->multiVehicleManager()->vehicles(), &QmlObjectListModel::countChanged, this, &Joystick::_vehicleCountChanged);
connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged);
connect(MultiVehicleManager::instance()->vehicles(), &QmlObjectListModel::countChanged, this, &Joystick::_vehicleCountChanged);
}

void Joystick::stop()
Expand Down Expand Up @@ -186,7 +185,7 @@ void Joystick::_loadSettings()
{
QSettings settings;
settings.beginGroup(_settingsGroup);
Vehicle* activeVehicle = _multiVehicleManager->activeVehicle();
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();

if(_txModeSettingsKey && activeVehicle)
_transmitterMode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt();
Expand Down Expand Up @@ -953,7 +952,7 @@ void Joystick::setCalibrationMode(bool calibrating)
_calibrationMode = calibrating;
if (calibrating && !isRunning()) {
_pollingStartedForCalibration = true;
startPolling(_multiVehicleManager->activeVehicle());
startPolling(MultiVehicleManager::instance()->activeVehicle());
}
else if (_pollingStartedForCalibration) {
stopPolling();
Expand Down
4 changes: 1 addition & 3 deletions src/Joystick/Joystick.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog)
Q_DECLARE_METATYPE(GRIPPER_ACTIONS)

class MultiVehicleManager;
class Vehicle;
class QmlObjectListModel;

Expand Down Expand Up @@ -63,7 +62,7 @@ class Joystick : public QThread
Q_MOC_INCLUDE("QmlObjectListModel.h")
Q_MOC_INCLUDE("Vehicle.h")
public:
Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager);
Joystick(const QString& name, int axisCount, int buttonCount, int hatCount);

virtual ~Joystick();

Expand Down Expand Up @@ -307,7 +306,6 @@ class Joystick : public QThread
QmlObjectListModel _assignableButtonActions;
QList<AssignedButtonAction*> _buttonActionArray;
QStringList _availableActionTitles;
MultiVehicleManager* _multiVehicleManager = nullptr;

CustomActionManager _customActionManager;

Expand Down
9 changes: 4 additions & 5 deletions src/Joystick/JoystickAndroid.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include "JoystickAndroid.h"
#include "JoystickManager.h"
#include "MultiVehicleManager.h"
#include "QGCLoggingCategory.h"

#include <QtCore/QJniEnvironment>
Expand All @@ -32,8 +31,8 @@ static void clear_jni_exception()
}
}

JoystickAndroid::JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id, MultiVehicleManager* multiVehicleManager)
: Joystick(name,axisCount,buttonCount,0,multiVehicleManager)
JoystickAndroid::JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id)
: Joystick(name,axisCount,buttonCount,0)
, deviceId(id)
{
int i;
Expand Down Expand Up @@ -95,7 +94,7 @@ JoystickAndroid::~JoystickAndroid() {
}


QMap<QString, Joystick*> JoystickAndroid::discover(MultiVehicleManager* _multiVehicleManager) {
QMap<QString, Joystick*> JoystickAndroid::discover() {
static QMap<QString, Joystick*> ret;

QMutexLocker lock(&m_mutex);
Expand Down Expand Up @@ -144,7 +143,7 @@ QMap<QString, Joystick*> JoystickAndroid::discover(MultiVehicleManager* _multiVe

qCDebug(JoystickLog) << "\t" << name << "id:" << buff[i] << "axes:" << axisCount << "buttons:" << buttonCount;

ret[name] = new JoystickAndroid(name, axisCount, buttonCount, buff[i], _multiVehicleManager);
ret[name] = new JoystickAndroid(name, axisCount, buttonCount, buff[i]);
}

for (auto i = ret.begin(); i != ret.end();) {
Expand Down
Loading

0 comments on commit 4508bb3

Please sign in to comment.