17#elif defined(Q_OS_ANDROID)
22#include <QtCore/QApplicationStatic>
23#include <QtCore/QTimer>
31 , _gcsHeartbeatTimer(new QTimer(this))
35 qCDebug(MultiVehicleManagerLog) <<
this;
40 qCDebug(MultiVehicleManagerLog) <<
this;
45 return _multiVehicleManagerInstance();
58 _gcsHeartbeatTimer->setInterval(kGCSHeartbeatRateMSecs);
59 _gcsHeartbeatTimer->setSingleShot(
false);
60 (void) connect(_gcsHeartbeatTimer, &QTimer::timeout,
this, &MultiVehicleManager::_sendGCSHeartbeat);
61 _gcsHeartbeatTimer->start();
66void MultiVehicleManager::_vehicleHeartbeatInfo(
LinkInterface* link,
int vehicleId,
int componentId,
int vehicleFirmwareType,
int vehicleType)
68 if (componentId != MAV_COMP_ID_AUTOPILOT1) {
70 qCDebug(MultiVehicleManagerLog) <<
"Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType"
74 << vehicleFirmwareType
79#ifndef QGC_NO_ARDUPILOT_DIALECT
83 if ((vehicleType == MAV_TYPE_GENERIC) && (vehicleFirmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA)) {
84 vehicleType = MAV_TYPE_QUADROTOR;
88 switch (vehicleType) {
90 case MAV_TYPE_ONBOARD_CONTROLLER:
103 if (_ignoreVehicleIds.contains(vehicleId) ||
getVehicleById(vehicleId) || (vehicleId == 0)) {
107 qCDebug(MultiVehicleManagerLog) <<
"Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType "
111 << vehicleFirmwareType
115 QGC::showAppMessage(tr(
"Warning: A vehicle is using the same system id as %1: %2").arg(QCoreApplication::applicationName()).arg(vehicleId));
118 Vehicle *
const vehicle =
new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType,
this);
122 _vehicles->
append(vehicle);
131 if (_vehicles->
count() > 1) {
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);
149void MultiVehicleManager::_deleteVehiclePhase1(
Vehicle *vehicle)
151 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
154 for (
int i = 0; i < _vehicles->
count(); i++) {
155 if (_vehicles->
get(i) == vehicle) {
163 qCWarning(MultiVehicleManagerLog) <<
"Vehicle not found in map!";
169 _setActiveVehicleAvailable(
false);
170 _setParameterReadyVehicleAvailable(
false);
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);
190 QTimer::singleShot(20,
this, [
this, vehicle]() {
191 _deleteVehiclePhase2(vehicle);
195void MultiVehicleManager::_deleteVehiclePhase2(
Vehicle *vehicle)
197 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
202 Vehicle *newActiveVehicle =
nullptr;
203 if (_vehicles->
count() > 0) {
204 newActiveVehicle = qobject_cast<Vehicle*>(_vehicles->
get(0));
207 _setActiveVehicle(newActiveVehicle);
209 if (_activeVehicle) {
210 _setActiveVehicleAvailable(
true);
212 _setParameterReadyVehicleAvailable(
true);
216 vehicle->deleteLater();
221 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
223 if (vehicle != _activeVehicle) {
224 if (_activeVehicle) {
230 _setActiveVehicleAvailable(
false);
231 _setParameterReadyVehicleAvailable(
false);
234 QTimer::singleShot(20,
this, [
this, vehicle]() {
235 _setActiveVehiclePhase2(vehicle);
240void MultiVehicleManager::_setActiveVehiclePhase2(
Vehicle *vehicle)
242 qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle;
244 _setActiveVehicle(vehicle);
246 if (_activeVehicle) {
247 _setActiveVehicleAvailable(
true);
250 _setParameterReadyVehicleAvailable(
true);
255void MultiVehicleManager::_vehicleParametersReadyChanged(
bool parametersReady)
257 ParameterManager *
const paramMgr = qobject_cast<ParameterManager*>(sender());
262 if (paramMgr->
vehicle() == _activeVehicle) {
263 _setParameterReadyVehicleAvailable(parametersReady);
267void MultiVehicleManager::_sendGCSHeartbeat()
280 if (linkConfiguration->isHighLatency()) {
285 (void) mavlink_msg_heartbeat_pack_chan(
291 MAV_AUTOPILOT_INVALID,
292 MAV_MODE_MANUAL_ARMED,
297 uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
298 const uint16_t len = mavlink_msg_to_send_buffer(buffer, &message);
305 if(!_vehicleSelected(vehicleId)) {
307 _selectedVehicles->
append(vehicle);
314 for (
int i = 0; i < _selectedVehicles->
count(); i++) {
315 Vehicle *
const vehicle = qobject_cast<Vehicle*>(_selectedVehicles->
get(i));
316 if (vehicle->
id() == vehicleId) {
325 _selectedVehicles->
clear();
328bool MultiVehicleManager::_vehicleSelected(
int vehicleId)
330 for (
int i = 0; i < _selectedVehicles->
count(); i++) {
331 Vehicle *
const vehicle = qobject_cast<Vehicle*>(_selectedVehicles->
get(i));
332 if (vehicle->
id() == vehicleId) {
341 for (
int i = 0; i < _vehicles->
count(); i++) {
342 Vehicle *
const vehicle = qobject_cast<Vehicle*>(_vehicles->
get(i));
343 if (vehicle->
id() == vehicleId) {
351void MultiVehicleManager::_setActiveVehicle(
Vehicle *vehicle)
353 if (vehicle != _activeVehicle) {
354 _activeVehicle = vehicle;
359void MultiVehicleManager::_setActiveVehicleAvailable(
bool activeVehicleAvailable)
361 if (activeVehicleAvailable != _activeVehicleAvailable) {
362 _activeVehicleAvailable = activeVehicleAvailable;
367void MultiVehicleManager::_setParameterReadyVehicleAvailable(
bool parametersReady)
369 if (parametersReady != _parameterReadyVehicleAvailable) {
370 _parameterReadyVehicleAvailable = parametersReady;
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()
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
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()
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
static const MAV_TYPE MAV_TYPE_TRACK
ParameterManager * parameterManager()
void setKeepScreenOn(bool on)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.