QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MultiVehicleManager.cc
Go to the documentation of this file.
2#include "MAVLinkProtocol.h"
3#include "AppMessages.h"
4#include "ParameterManager.h"
5#include "SettingsManager.h"
6#include "MavlinkSettings.h"
8#include "QGCCorePlugin.h"
9#include "QGCOptions.h"
10#include "LinkManager.h"
11#include "Vehicle.h"
12#include "VehicleLinkManager.h"
13#include "LinkInterface.h"
14#include "QmlObjectListModel.h"
15#ifdef Q_OS_IOS
16#include "MobileScreenMgr.h"
17#elif defined(Q_OS_ANDROID)
18#include "AndroidInterface.h"
19#endif
20#include "QGCLoggingCategory.h"
21
22#include <QtCore/QApplicationStatic>
23#include <QtCore/QTimer>
24
25QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "Vehicle.MultiVehicleManager")
26
27Q_APPLICATION_STATIC(MultiVehicleManager, _multiVehicleManagerInstance);
28
30 : QObject(parent)
31 , _gcsHeartbeatTimer(new QTimer(this))
32 , _vehicles(new QmlObjectListModel(this))
33 , _selectedVehicles(new QmlObjectListModel(this))
34{
35 qCDebug(MultiVehicleManagerLog) << this;
36}
37
39{
40 qCDebug(MultiVehicleManagerLog) << this;
41}
42
44{
45 return _multiVehicleManagerInstance();
46}
47
49{
50 if (_initialized) {
51 return;
52 }
53
54 _offlineEditingVehicle = new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, this);
55
56 (void) connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
57
58 _gcsHeartbeatTimer->setInterval(kGCSHeartbeatRateMSecs);
59 _gcsHeartbeatTimer->setSingleShot(false);
60 (void) connect(_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
61 _gcsHeartbeatTimer->start();
62
63 _initialized = true;
64}
65
66void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
67{
68 if (componentId != MAV_COMP_ID_AUTOPILOT1) {
69 // Don't create vehicles for components other than the autopilot
70 qCDebug(MultiVehicleManagerLog) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType"
71 << link->linkConfiguration()->name()
72 << vehicleId
73 << componentId
74 << vehicleFirmwareType
75 << vehicleType;
76 return;
77 }
78
79#ifndef QGC_NO_ARDUPILOT_DIALECT
80 // When you flash a new ArduCopter it does not set a FRAME_CLASS for some reason. This is the only ArduPilot variant which
81 // works this way. Because of this the vehicle type is not known at first connection. In order to make QGC work reasonably
82 // we assume ArduCopter for this case.
83 if ((vehicleType == MAV_TYPE_GENERIC) && (vehicleFirmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA)) {
84 vehicleType = MAV_TYPE_QUADROTOR;
85 }
86#endif
87
88 switch (vehicleType) {
89 case MAV_TYPE_GCS:
90 case MAV_TYPE_ONBOARD_CONTROLLER:
91 case MAV_TYPE_GIMBAL:
92 case MAV_TYPE_ADSB:
93 // These are not vehicles, so don't create a vehicle for them
94 return;
95 default:
96 break;
97 }
98
99 if ((_vehicles->count() > 0) && !QGCCorePlugin::instance()->options()->multiVehicleEnabled()) {
100 return;
101 }
102
103 if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || (vehicleId == 0)) {
104 return;
105 }
106
107 qCDebug(MultiVehicleManagerLog) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType "
108 << link->linkConfiguration()->name()
109 << vehicleId
110 << componentId
111 << vehicleFirmwareType
112 << vehicleType;
113
114 if (vehicleId == MAVLinkProtocol::instance()->getSystemId()) {
115 QGC::showAppMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(QCoreApplication::applicationName()).arg(vehicleId));
116 }
117
118 Vehicle *const vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, this);
119 (void) connect(vehicle->vehicleLinkManager(), &VehicleLinkManager::allLinksRemoved, this, &MultiVehicleManager::_deleteVehiclePhase1);
120 (void) connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged);
121
122 _vehicles->append(vehicle);
123
124 // Send QGC heartbeat ASAP, this allows PX4 to start accepting commands
125 _sendGCSHeartbeat();
126
127 SettingsManager::instance()->firmwareUpgradeSettings()->defaultFirmwareType()->setRawValue(vehicleFirmwareType);
128
129 emit vehicleAdded(vehicle);
130
131 if (_vehicles->count() > 1) {
132 QGC::showAppMessage(tr("Connected to Vehicle %1").arg(vehicleId));
133 } else {
134 setActiveVehicle(vehicle);
135 }
136
137#if defined(Q_OS_ANDROID) || defined(Q_OS_IOS)
138 if (_vehicles->count() == 1) {
139 qCDebug(MultiVehicleManagerLog) << "keepScreenOn";
140 #if defined(Q_OS_ANDROID)
142 #elif defined(Q_OS_IOS)
143 MobileScreenMgr::setKeepScreenOn(true);
144 #endif
145 }
146#endif
147}
148
149void MultiVehicleManager::_deleteVehiclePhase1(Vehicle *vehicle)
150{
151 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
152
153 bool found = false;
154 for (int i = 0; i < _vehicles->count(); i++) {
155 if (_vehicles->get(i) == vehicle) {
156 (void) _vehicles->removeAt(i);
157 found = true;
158 break;
159 }
160 }
161
162 if (!found) {
163 qCWarning(MultiVehicleManagerLog) << "Vehicle not found in map!";
164 return;
165 }
166
167 deselectVehicle(vehicle->id());
168
169 _setActiveVehicleAvailable(false);
170 _setParameterReadyVehicleAvailable(false);
171 emit vehicleRemoved(vehicle);
172
173#if defined(Q_OS_ANDROID) || defined (Q_OS_IOS)
174 if (_vehicles->count() == 0) {
175 qCDebug(MultiVehicleManagerLog) << "restoreScreenOn";
176 #if defined(Q_OS_ANDROID)
178 #elif defined(Q_OS_IOS)
179 MobileScreenMgr::setKeepScreenOn(false);
180 #endif
181 }
182#endif
183
184 // We must let the above signals flow through the system as well as get back to the main loop event queue
185 // before we can actually delete the Vehicle. The reason is that Qml may be holding on to references to it.
186 // Even though the above signals should unload any Qml which has references, that Qml will not be destroyed
187 // until we get back to the main loop. So we set a short timer which will then fire after Qt has finished
188 // doing all of its internal nastiness to clean up the Qml. This works for both the normal running case
189 // as well as the unit testing case which of course has a different signal flow!
190 QTimer::singleShot(20, this, [this, vehicle]() {
191 _deleteVehiclePhase2(vehicle);
192 });
193}
194
195void MultiVehicleManager::_deleteVehiclePhase2(Vehicle *vehicle)
196{
197 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
198
201
202 Vehicle *newActiveVehicle = nullptr;
203 if (_vehicles->count() > 0) {
204 newActiveVehicle = qobject_cast<Vehicle*>(_vehicles->get(0));
205 }
206
207 _setActiveVehicle(newActiveVehicle);
208
209 if (_activeVehicle) {
210 _setActiveVehicleAvailable(true);
211 if (_activeVehicle->parameterManager()->parametersReady()) {
212 _setParameterReadyVehicleAvailable(true);
213 }
214 }
215
216 vehicle->deleteLater();
217}
218
220{
221 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
222
223 if (vehicle != _activeVehicle) {
224 if (_activeVehicle) {
225 // The sequence of signals is very important in order to not leave Qml elements connected
226 // to a non-existent vehicle.
227
228 // First we must signal that there is no active vehicle available. This will disconnect
229 // any existing ui from the currently active vehicle.
230 _setActiveVehicleAvailable(false);
231 _setParameterReadyVehicleAvailable(false);
232 }
233
234 QTimer::singleShot(20, this, [this, vehicle]() {
235 _setActiveVehiclePhase2(vehicle);
236 });
237 }
238}
239
240void MultiVehicleManager::_setActiveVehiclePhase2(Vehicle *vehicle)
241{
242 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
243
244 _setActiveVehicle(vehicle);
245
246 if (_activeVehicle) {
247 _setActiveVehicleAvailable(true);
248
249 if (_activeVehicle->parameterManager()->parametersReady()) {
250 _setParameterReadyVehicleAvailable(true);
251 }
252 }
253}
254
255void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady)
256{
257 ParameterManager *const paramMgr = qobject_cast<ParameterManager*>(sender());
258 if (!paramMgr) {
259 return;
260 }
261
262 if (paramMgr->vehicle() == _activeVehicle) {
263 _setParameterReadyVehicleAvailable(parametersReady);
264 }
265}
266
267void MultiVehicleManager::_sendGCSHeartbeat()
268{
269 if (!SettingsManager::instance()->mavlinkSettings()->sendGCSHeartbeat()->rawValue().toBool()) {
270 return;
271 }
272
273 const QList<SharedLinkInterfacePtr> sharedLinks = LinkManager::instance()->links();
274 for (const SharedLinkInterfacePtr &link: sharedLinks) {
275 if (!link->isConnected()) {
276 continue;
277 }
278
279 const SharedLinkConfigurationPtr linkConfiguration = link->linkConfiguration();
280 if (linkConfiguration->isHighLatency()) {
281 continue;
282 }
283
284 mavlink_message_t message{};
285 (void) mavlink_msg_heartbeat_pack_chan(
288 link->mavlinkChannel(),
289 &message,
290 MAV_TYPE_GCS,
291 MAV_AUTOPILOT_INVALID,
292 MAV_MODE_MANUAL_ARMED,
293 0,
294 MAV_STATE_ACTIVE
295 );
296
297 uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
298 const uint16_t len = mavlink_msg_to_send_buffer(buffer, &message);
299 (void) link->writeBytesThreadSafe(reinterpret_cast<const char*>(buffer), len);
300 }
301}
302
304{
305 if(!_vehicleSelected(vehicleId)) {
306 Vehicle *const vehicle = getVehicleById(vehicleId);
307 _selectedVehicles->append(vehicle);
308 return;
309 }
310}
311
313{
314 for (int i = 0; i < _selectedVehicles->count(); i++) {
315 Vehicle *const vehicle = qobject_cast<Vehicle*>(_selectedVehicles->get(i));
316 if (vehicle->id() == vehicleId) {
317 _selectedVehicles->removeAt(i);
318 return;
319 }
320 }
321}
322
324{
325 _selectedVehicles->clear();
326}
327
328bool MultiVehicleManager::_vehicleSelected(int vehicleId)
329{
330 for (int i = 0; i < _selectedVehicles->count(); i++) {
331 Vehicle *const vehicle = qobject_cast<Vehicle*>(_selectedVehicles->get(i));
332 if (vehicle->id() == vehicleId) {
333 return true;
334 }
335 }
336 return false;
337}
338
340{
341 for (int i = 0; i < _vehicles->count(); i++) {
342 Vehicle *const vehicle = qobject_cast<Vehicle*>(_vehicles->get(i));
343 if (vehicle->id() == vehicleId) {
344 return vehicle;
345 }
346 }
347
348 return nullptr;
349}
350
351void MultiVehicleManager::_setActiveVehicle(Vehicle *vehicle)
352{
353 if (vehicle != _activeVehicle) {
354 _activeVehicle = vehicle;
355 emit activeVehicleChanged(vehicle);
356 }
357}
358
359void MultiVehicleManager::_setActiveVehicleAvailable(bool activeVehicleAvailable)
360{
361 if (activeVehicleAvailable != _activeVehicleAvailable) {
362 _activeVehicleAvailable = activeVehicleAvailable;
363 emit activeVehicleAvailableChanged(activeVehicleAvailable);
364 }
365}
366
367void MultiVehicleManager::_setParameterReadyVehicleAvailable(bool parametersReady)
368{
369 if (parametersReady != _parameterReadyVehicleAvailable) {
370 _parameterReadyVehicleAvailable = parametersReady;
372 }
373}
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Q_APPLICATION_STATIC(MultiVehicleManager, _multiVehicleManagerInstance)
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
The link interface defines the interface for all links used to communicate with the ground station ap...
uint8_t mavlinkChannel() const
virtual bool isConnected() const =0
void writeBytesThreadSafe(const char *bytes, int length)
SharedLinkConfigurationPtr linkConfiguration()
static LinkManager * instance()
QList< SharedLinkInterfacePtr > links()
static int getComponentId()
void vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
static MAVLinkProtocol * instance()
int getSystemId() const
static MultiVehicleManager * instance()
void activeVehicleAvailableChanged(bool activeVehicleAvailable)
Q_INVOKABLE void deselectAllVehicles()
Q_INVOKABLE void selectVehicle(int vehicleId)
void vehicleAdded(Vehicle *vehicle)
Q_INVOKABLE void deselectVehicle(int vehicleId)
void vehicleRemoved(Vehicle *vehicle)
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable)
void activeVehicleChanged(Vehicle *activeVehicle)
Q_INVOKABLE Vehicle * getVehicleById(int vehicleId) const
void setActiveVehicle(Vehicle *vehicle)
void parametersReadyChanged(bool parametersReady)
bool parametersReady() const
virtual QGCOptions * options()
static QGCCorePlugin * instance()
virtual bool multiVehicleEnabled() const
Definition QGCOptions.h:123
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
Q_INVOKABLE QObject * get(int index)
QObject * removeAt(int index)
int count() const override final
void clear() override final
FirmwareUpgradeSettings * firmwareUpgradeSettings() const
static SettingsManager * instance()
void allLinksRemoved(Vehicle *vehicle)
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int id() const
Definition Vehicle.h:425
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
Definition Vehicle.h:127
static const MAV_TYPE MAV_TYPE_TRACK
Definition Vehicle.h:128
ParameterManager * parameterManager()
Definition Vehicle.h:573
void setKeepScreenOn(bool on)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9