QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MultiVehicleManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QLoggingCategory>
5#include <QtQmlIntegration/QtQmlIntegration>
6
7class LinkInterface;
8class Vehicle;
10class QTimer;
11
12Q_DECLARE_LOGGING_CATEGORY(MultiVehicleManagerLog)
13
14class MultiVehicleManager : public QObject
15{
16 Q_OBJECT
17 QML_ELEMENT
18 QML_UNCREATABLE("")
19 Q_MOC_INCLUDE("QmlObjectListModel.h")
20 Q_MOC_INCLUDE("LinkInterface.h")
21 Q_MOC_INCLUDE("Vehicle.h")
22 Q_PROPERTY(bool activeVehicleAvailable READ _getActiveVehicleAvailable NOTIFY activeVehicleAvailableChanged)
23 Q_PROPERTY(bool parameterReadyVehicleAvailable READ _getParameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
24 Q_PROPERTY(Vehicle *activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
25 Q_PROPERTY(QmlObjectListModel *vehicles READ vehicles CONSTANT)
26 Q_PROPERTY(QmlObjectListModel *selectedVehicles READ selectedVehicles CONSTANT)
27 Q_PROPERTY(Vehicle *offlineEditingVehicle READ offlineEditingVehicle CONSTANT)
28
29public:
30 explicit MultiVehicleManager(QObject *parent = nullptr);
32
33 static MultiVehicleManager *instance();
34 static void registerQmlTypes();
35
36 void init();
37 Q_INVOKABLE Vehicle *getVehicleById(int vehicleId) const;
38 Q_INVOKABLE void selectVehicle(int vehicleId);
39 Q_INVOKABLE void deselectVehicle(int vehicleId);
40 Q_INVOKABLE void deselectAllVehicles();
41 QmlObjectListModel *vehicles() const { return _vehicles; }
42 QmlObjectListModel *selectedVehicles() const { return _selectedVehicles; }
43 Vehicle *offlineEditingVehicle() const { return _offlineEditingVehicle; }
44 Vehicle *activeVehicle() const { return _activeVehicle; }
45 void setActiveVehicle(Vehicle *vehicle);
46
47signals:
48 void vehicleAdded(Vehicle *vehicle);
49 void vehicleRemoved(Vehicle *vehicle);
50 void activeVehicleAvailableChanged(bool activeVehicleAvailable);
51 void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable);
52 void activeVehicleChanged(Vehicle *activeVehicle);
53
54private slots:
55 void _deleteVehiclePhase1(Vehicle *vehicle);
56 void _deleteVehiclePhase2(Vehicle *vehicle);
57 void _setActiveVehiclePhase2(Vehicle *vehicle);
58 void _vehicleParametersReadyChanged(bool parametersReady);
59 void _sendGCSHeartbeat();
60 void _vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
61
62private:
63 bool _vehicleExists(int vehicleId);
64 bool _vehicleSelected(int vehicleId);
65 void _setActiveVehicle(Vehicle *vehicle);
66 bool _getActiveVehicleAvailable() const { return _activeVehicleAvailable; }
67 void _setActiveVehicleAvailable(bool activeVehicleAvailable);
68 bool _getParameterReadyVehicleAvailable() const { return _parameterReadyVehicleAvailable; }
69 void _setParameterReadyVehicleAvailable(bool parametersReady);
70
71 QTimer *_gcsHeartbeatTimer = nullptr;
72 QmlObjectListModel *_vehicles = nullptr;
73 QmlObjectListModel *_selectedVehicles = nullptr;
74 Vehicle *_offlineEditingVehicle = nullptr;
75 bool _activeVehicleAvailable = false;
76 bool _parameterReadyVehicleAvailable = false;
77 Vehicle *_activeVehicle = nullptr;
78 QList<int> _ignoreVehicleIds;
79 bool _initialized = false;
80
81 static constexpr int kGCSHeartbeatRateMSecs = 1000;
82};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
The link interface defines the interface for all links used to communicate with the ground station ap...
void activeVehicleAvailableChanged(bool activeVehicleAvailable)
void vehicleAdded(Vehicle *vehicle)
void vehicleRemoved(Vehicle *vehicle)
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable)
void activeVehicleChanged(Vehicle *activeVehicle)