Newer
Older
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Brief Description
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QApplication>
#include <QDebug>
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")
const char* LinkManager::_settingsGroup = "LinkManager";
const char* LinkManager::_autoconnectUDPKey = "AutoconnectUDP";
const char* LinkManager::_autoconnectPixhawkKey = "AutoconnectPixhawk";
const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio";
const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow";
const char* LinkManager::_defaultUPDLinkName = "Default UDP Link";
dogmaphobic
committed
const int LinkManager::_autoconnectUpdateTimerMSecs = 1000;
#ifdef Q_OS_WIN
// Have to manually let the bootloader go by on Windows to get a working connect
const int LinkManager::_autoconnectConnectDelayMSecs = 6000;
#else
const int LinkManager::_autoconnectConnectDelayMSecs = 1000;
#endif
LinkManager::LinkManager(QGCApplication* app)
: QGCTool(app)
dogmaphobic
committed
, _configUpdateSuspended(false)
, _configurationsLoaded(false)
, _connectionsSuspended(false)
, _mavlinkChannelsUsedBitMask(1) // We never use channel 0 to avoid sequence numbering problems
, _autoconnectUDP(true)
, _autoconnectPixhawk(true)
, _autoconnect3DRRadio(true)
, _autoconnectPX4Flow(true)
qmlRegisterUncreatableType<LinkManager> ("QGroundControl", 1, 0, "LinkManager", "Reference only");
qmlRegisterUncreatableType<LinkConfiguration> ("QGroundControl", 1, 0, "LinkConfiguration", "Reference only");
qmlRegisterUncreatableType<LinkInterface> ("QGroundControl", 1, 0, "LinkInterface", "Reference only");
QSettings settings;
settings.beginGroup(_settingsGroup);
_autoconnectUDP = settings.value(_autoconnectUDPKey, true).toBool();
_autoconnectPixhawk = settings.value(_autoconnectPixhawkKey, true).toBool();
_autoconnect3DRRadio = settings.value(_autoconnect3DRRadioKey, true).toBool();
_autoconnectPX4Flow = settings.value(_autoconnectPX4FlowKey, true).toBool();
_activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
_activeLinkCheckTimer.setSingleShot(false);
connect(&_activeLinkCheckTimer, &QTimer::timeout, this, &LinkManager::_activeLinkCheck);
void LinkManager::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
_mavlinkProtocol = _toolbox->mavlinkProtocol();
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
_portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config)
dogmaphobic
committed
{
Q_ASSERT(config);
LinkInterface* pLink = NULL;
switch(config->type()) {
dogmaphobic
committed
case LinkConfiguration::TypeSerial:
{
SerialConfiguration* serialConfig = dynamic_cast<SerialConfiguration*>(config);
if (serialConfig) {
pLink = new SerialLink(serialConfig);
if (serialConfig->usbDirect()) {
_activeLinkCheckList.append((SerialLink*)pLink);
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
}
}
}
break;
dogmaphobic
committed
case LinkConfiguration::TypeUdp:
pLink = new UDPLink(dynamic_cast<UDPConfiguration*>(config));
break;
case LinkConfiguration::TypeTcp:
pLink = new TCPLink(dynamic_cast<TCPConfiguration*>(config));
break;
case LinkConfiguration::TypeBluetooth:
pLink = new BluetoothLink(dynamic_cast<BluetoothConfiguration*>(config));
break;
#endif
case LinkConfiguration::TypeLogReplay:
pLink = new LogReplayLink(dynamic_cast<LogReplayLinkConfiguration*>(config));
break;
dogmaphobic
committed
case LinkConfiguration::TypeMock:
pLink = new MockLink(dynamic_cast<MockConfiguration*>(config));
break;
case LinkConfiguration::TypeLast:
default:
break;
dogmaphobic
committed
}
if(pLink) {
_addLink(pLink);
connectLink(pLink);
dogmaphobic
committed
}
return pLink;
}
LinkInterface* LinkManager::createConnectedLink(const QString& name)
dogmaphobic
committed
{
Q_ASSERT(name.isEmpty() == false);
for(int i = 0; i < _linkConfigurations.count(); i++) {
LinkConfiguration* conf = _linkConfigurations.value<LinkConfiguration*>(i);
dogmaphobic
committed
if(conf && conf->name() == name)
dogmaphobic
committed
}
return NULL;
}
void LinkManager::_addLink(LinkInterface* link)
if (thread() != QThread::currentThread()) {
qWarning() << "_deleteLink called from incorrect thread";
return;
}
dogmaphobic
committed
dogmaphobic
committed
// Find a mavlink channel to use for this link
for (int i=0; i<32; i++) {
if (!(_mavlinkChannelsUsedBitMask & 1 << i)) {
link->_setMavlinkChannel(i);
_mavlinkChannelsUsedBitMask |= i << i;
if (!channelSet) {
qWarning() << "Ran out of mavlink channels";
}
emit newLink(link);
}
dogmaphobic
committed
connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);
dogmaphobic
committed
_mavlinkProtocol->resetMetadataForLink(link);
dogmaphobic
committed
connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected);
connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
// This connection is queued since it will cloe the link. So we want the link emitter to return otherwise we would
// close the link our from under itself.
connect(link, &LinkInterface::connectionRemoved, this, &LinkManager::_linkConnectionRemoved, Qt::QueuedConnection);
}
// Walk list in reverse order to preserve indices during delete
for (int i=_links.count()-1; i>=0; i--) {
}
bool LinkManager::connectLink(LinkInterface* link)
{
dogmaphobic
committed
if (_connectionsSuspendedMsg()) {
return false;
}
void LinkManager::disconnectLink(LinkInterface* link)
if (!link || !_links.contains(link)) {
return;
}
link->_disconnect();
LinkConfiguration* config = link->getLinkConfiguration();
if (config) {
if (_autoconnectConfigurations.contains(config)) {
config->setLink(NULL);
}
if (_autoconnectConfigurations.contains(config)) {
qCDebug(LinkManagerLog) << "Removing disconnected autoconnect config" << config->name();
_autoconnectConfigurations.removeOne(config);
delete config;
}
void LinkManager::_deleteLink(LinkInterface* link)
if (thread() != QThread::currentThread()) {
qWarning() << "_deleteLink called from incorrect thread";
return;
}
if (!link) {
return;
}
dogmaphobic
committed
// Free up the mavlink channel associated with this link
_mavlinkChannelsUsedBitMask &= ~(1 << link->getMavlinkChannel());
dogmaphobic
committed
dogmaphobic
committed
/// @brief If all new connections should be suspended a message is displayed to the user and true
/// is returned;
bool LinkManager::_connectionsSuspendedMsg(void)
{
if (_connectionsSuspended) {
qgcApp()->showMessage(QString("Connect not allowed: %1").arg(_connectionsSuspendedReason));
return true;
} else {
return false;
}
}
void LinkManager::setConnectionsSuspended(QString reason)
{
_connectionsSuspended = true;
_connectionsSuspendedReason = reason;
Q_ASSERT(!reason.isEmpty());
}
void LinkManager::_linkConnected(void)
{
emit linkConnected((LinkInterface*)sender());
}
void LinkManager::_linkDisconnected(void)
{
emit linkDisconnected((LinkInterface*)sender());
}
dogmaphobic
committed
void LinkManager::_linkConnectionRemoved(LinkInterface* link)
{
// Link has been removed from system, disconnect it automatically
disconnectLink(link);
}
dogmaphobic
committed
void LinkManager::suspendConfigurationUpdates(bool suspend)
{
_configUpdateSuspended = suspend;
}
void LinkManager::saveLinkConfigurationList()
{
QSettings settings;
settings.remove(LinkConfiguration::settingsRoot());
int trueCount = 0;
for (int i = 0; i < _linkConfigurations.count(); i++) {
LinkConfiguration* linkConfig = _linkConfigurations.value<LinkConfiguration*>(i);
if (linkConfig) {
if(!linkConfig->isDynamic())
{
QString root = LinkConfiguration::settingsRoot();
root += QString("/Link%1").arg(trueCount++);
settings.setValue(root + "/name", linkConfig->name());
settings.setValue(root + "/type", linkConfig->type());
settings.setValue(root + "/auto", linkConfig->isAutoConnect());
// Have the instance save its own values
linkConfig->saveSettings(settings, root);
}
} else {
qWarning() << "Internal error";
dogmaphobic
committed
}
settings.setValue(root + "/count", trueCount);
emit linkConfigurationsChanged();
dogmaphobic
committed
}
void LinkManager::loadLinkConfigurationList()
{
dogmaphobic
committed
QSettings settings;
// Is the group even there?
if(settings.contains(LinkConfiguration::settingsRoot() + "/count")) {
// Find out how many configurations we have
int count = settings.value(LinkConfiguration::settingsRoot() + "/count").toInt();
for(int i = 0; i < count; i++) {
QString root(LinkConfiguration::settingsRoot());
root += QString("/Link%1").arg(i);
if(settings.contains(root + "/type")) {
int type = settings.value(root + "/type").toInt();
if((LinkConfiguration::LinkType)type < LinkConfiguration::TypeLast) {
dogmaphobic
committed
if(settings.contains(root + "/name")) {
QString name = settings.value(root + "/name").toString();
if(!name.isEmpty()) {
LinkConfiguration* pLink = NULL;
bool autoConnect = settings.value(root + "/auto").toBool();
switch((LinkConfiguration::LinkType)type) {
dogmaphobic
committed
case LinkConfiguration::TypeSerial:
pLink = (LinkConfiguration*)new SerialConfiguration(name);
break;
dogmaphobic
committed
case LinkConfiguration::TypeUdp:
pLink = (LinkConfiguration*)new UDPConfiguration(name);
break;
case LinkConfiguration::TypeTcp:
pLink = (LinkConfiguration*)new TCPConfiguration(name);
break;
case LinkConfiguration::TypeBluetooth:
pLink = (LinkConfiguration*)new BluetoothConfiguration(name);
break;
#endif
case LinkConfiguration::TypeLogReplay:
pLink = (LinkConfiguration*)new LogReplayLinkConfiguration(name);
break;
dogmaphobic
committed
case LinkConfiguration::TypeMock:
pLink = (LinkConfiguration*)new MockConfiguration(name);
dogmaphobic
committed
break;
default:
case LinkConfiguration::TypeLast:
break;
dogmaphobic
committed
}
if(pLink) {
//-- Have the instance load its own values
pLink->setAutoConnect(autoConnect);
dogmaphobic
committed
pLink->loadSettings(settings, root);
dogmaphobic
committed
}
} else {
qWarning() << "Link Configuration" << root << "has an empty name." ;
dogmaphobic
committed
}
} else {
qWarning() << "Link Configuration" << root << "has no name." ;
dogmaphobic
committed
}
} else {
qWarning() << "Link Configuration" << root << "an invalid type: " << type;
dogmaphobic
committed
}
} else {
qWarning() << "Link Configuration" << root << "has no type." ;
dogmaphobic
committed
}
}
}
// Debug buids always add MockLink automatically (if one is not already there)
if(!mockPresent)
{
MockConfiguration* pMock = new MockConfiguration("Mock Link PX4");
pMock->setDynamic(true);
_linkConfigurations.append(pMock);
linksChanged = true;
}
}
// Enable automatic Serial PX4/3DR Radio hunting
dogmaphobic
committed
_configurationsLoaded = true;
}
SerialConfiguration* LinkManager::_autoconnectConfigurationsContainsPort(const QString& portName)
dogmaphobic
committed
{
QString searchPort = portName.trimmed();
for (int i=0; i<_autoconnectConfigurations.count(); i++) {
SerialConfiguration* linkConfig = _autoconnectConfigurations.value<SerialConfiguration*>(i);
if (linkConfig) {
if (linkConfig->portName() == searchPort) {
return linkConfig;
dogmaphobic
committed
}
dogmaphobic
committed
}
}
return NULL;
}
dogmaphobic
committed
dogmaphobic
committed
{
if (_connectionsSuspended || qgcApp()->runningUnitTests()) {
dogmaphobic
committed
return;
}
// Re-add UDP if we need to
bool foundUDP = false;
for (int i=0; i<_links.count(); i++) {
LinkConfiguration* linkConfig = _links.value<LinkInterface*>(i)->getLinkConfiguration();
if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _defaultUPDLinkName) {
foundUDP = true;
break;
}
}
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT);
udpConfig->setDynamic(true);
_linkConfigurations.append(udpConfig);
QList<QGCSerialPortInfo> portList = QGCSerialPortInfo::availablePorts();
dogmaphobic
committed
// Iterate Comm Ports
qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName();
qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation();
qCDebug(LinkManagerVerboseLog) << "description: " << portInfo.description();
qCDebug(LinkManagerVerboseLog) << "manufacturer: " << portInfo.manufacturer();
qCDebug(LinkManagerVerboseLog) << "serialNumber: " << portInfo.serialNumber();
qCDebug(LinkManagerVerboseLog) << "vendorIdentifier: " << portInfo.vendorIdentifier();
qCDebug(LinkManagerVerboseLog) << "productIdentifier: " << portInfo.productIdentifier();
// Save port name
currentPorts << portInfo.systemLocation();
QGCSerialPortInfo::BoardType_t boardType = portInfo.boardType();
if (boardType != QGCSerialPortInfo::BoardTypeUnknown) {
if (portInfo.isBootloader()) {
// Don't connect to bootloader
qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
if (_autoconnectConfigurationsContainsPort(portInfo.systemLocation())) {
qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
} else if (!_autoconnectWaitList.contains(portInfo.systemLocation())) {
// We don't connect to the port the first time we see it. The ability to correctly detect whether we
// are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list
// and only connect on the second pass we leave enough time for the board to boot up.
qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation();
_autoconnectWaitList[portInfo.systemLocation()] = 1;
} else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
_autoconnectWaitList.remove(portInfo.systemLocation());
switch (boardType) {
case QGCSerialPortInfo::BoardTypePX4FMUV1:
case QGCSerialPortInfo::BoardTypePX4FMUV2:
if (_autoconnectPixhawk) {
pSerialConfig = new SerialConfiguration(QString("Pixhawk on %1").arg(portInfo.portName().trimmed()));
pSerialConfig->setUsbDirect(true);
break;
case QGCSerialPortInfo::BoardTypeAeroCore:
if (_autoconnectPixhawk) {
pSerialConfig = new SerialConfiguration(QString("AeroCore on %1").arg(portInfo.portName().trimmed()));
pSerialConfig->setUsbDirect(true);
break;
case QGCSerialPortInfo::BoardTypePX4Flow:
if (_autoconnectPX4Flow) {
pSerialConfig = new SerialConfiguration(QString("PX4Flow on %1").arg(portInfo.portName().trimmed()));
}
pSerialConfig = new SerialConfiguration(QString("SiK Radio on %1").arg(portInfo.portName().trimmed()));
if (pSerialConfig) {
qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
pSerialConfig->setBaud(boardType == QGCSerialPortInfo::BoardTypeSikRadio ? 57600 : 115200);
pSerialConfig->setDynamic(true);
pSerialConfig->setPortName(portInfo.systemLocation());
_autoconnectConfigurations.append(pSerialConfig);
// Now we go through the current configuration list and make sure any dynamic config has gone away
QList<LinkConfiguration*> _confToDelete;
for (int i=0; i<_autoconnectConfigurations.count(); i++) {
SerialConfiguration* linkConfig = _autoconnectConfigurations.value<SerialConfiguration*>(i);
if (linkConfig) {
if (!currentPorts.contains(linkConfig->portName())) {
if (linkConfig->link()) {
if (linkConfig->link()->isConnected()) {
if (linkConfig->link()->active()) {
// We don't remove links which are still connected which have been active with a vehicle on them
// even though at this point the cable may have been pulled. Instead we wait for the user to
// Disconnect. Once the user disconnects, the link will be removed.
continue;
}
}
foreach (LinkConfiguration* pDeleteConfig, _confToDelete) {
qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name();
if (pDeleteConfig->link()) {
disconnectLink(pDeleteConfig->link());
}
dogmaphobic
committed
}
dogmaphobic
committed
}
void LinkManager::shutdown(void)
{
setConnectionsSuspended("Shutdown");
}
void LinkManager::setAutoconnectUDP(bool autoconnect)
{
if (_autoconnectUDP != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectUDPKey, autoconnect);
_autoconnectUDP = autoconnect;
emit autoconnectUDPChanged(autoconnect);
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
}
void LinkManager::setAutoconnectPixhawk(bool autoconnect)
{
if (_autoconnectPixhawk != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectPixhawkKey, autoconnect);
_autoconnectPixhawk = autoconnect;
emit autoconnectPixhawkChanged(autoconnect);
}
}
void LinkManager::setAutoconnect3DRRadio(bool autoconnect)
{
if (_autoconnect3DRRadio != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnect3DRRadioKey, autoconnect);
_autoconnect3DRRadio = autoconnect;
emit autoconnect3DRRadioChanged(autoconnect);
}
}
void LinkManager::setAutoconnectPX4Flow(bool autoconnect)
{
if (_autoconnectPX4Flow != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectPX4FlowKey, autoconnect);
_autoconnectPX4Flow = autoconnect;
emit autoconnectPX4FlowChanged(autoconnect);
}
QStringList LinkManager::linkTypeStrings(void) const
{
//-- Must follow same order as enum LinkType in LinkConfiguration.h
static QStringList list;
if(!list.size())
{
#ifndef __ios__
list += "Serial";
#endif
list += "UDP";
list += "TCP";
Q_ASSERT(list.size() == (int)LinkConfiguration::TypeLast);
void LinkManager::_updateSerialPorts()
_commPortList.clear();
_commPortDisplayList.clear();
QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
foreach (const QSerialPortInfo &info, portList)
QString port = info.systemLocation().trimmed();
_commPortList += port;
_commPortDisplayList += SerialConfiguration::cleanPortDisplayname(port);
}
QStringList LinkManager::serialPortStrings(void)
{
if(!_commPortDisplayList.size())
{
_updateSerialPorts();
}
return _commPortDisplayList;
}
QStringList LinkManager::serialPorts(void)
{
if(!_commPortList.size())
{
_updateSerialPorts();
}
return _commPortList;
}
QStringList LinkManager::serialBaudRates(void)
{
#ifdef __ios__
QStringList foo;
return foo;
#else
return SerialConfiguration::supportedBaudRates();
#endif
}
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
bool LinkManager::endConfigurationEditing(LinkConfiguration* config, LinkConfiguration* editedConfig)
{
Q_ASSERT(config != NULL);
Q_ASSERT(editedConfig != NULL);
_fixUnnamed(editedConfig);
config->copyFrom(editedConfig);
saveLinkConfigurationList();
// Tell link about changes (if any)
config->updateSettings();
// Discard temporary duplicate
delete editedConfig;
return true;
}
bool LinkManager::endCreateConfiguration(LinkConfiguration* config)
{
Q_ASSERT(config != NULL);
_fixUnnamed(config);
_linkConfigurations.append(config);
saveLinkConfigurationList();
return true;
}
LinkConfiguration* LinkManager::createConfiguration(int type, const QString& name)
{
if((LinkConfiguration::LinkType)type == LinkConfiguration::TypeSerial)
_updateSerialPorts();
return LinkConfiguration::createSettings(type, name);
}
LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* config)
{
Q_ASSERT(config != NULL);
if(config->type() == LinkConfiguration::TypeSerial)
_updateSerialPorts();
return LinkConfiguration::duplicateSettings(config);
}
void LinkManager::_fixUnnamed(LinkConfiguration* config)
{
Q_ASSERT(config != NULL);
//-- Check for "Unnamed"
if (config->name() == "Unnamed") {
switch(config->type()) {
#ifndef __ios__
case LinkConfiguration::TypeSerial: {
QString tname = dynamic_cast<SerialConfiguration*>(config)->portName();
tname.replace("\\\\.\\", "");
#else
tname.replace("/dev/cu.", "");
tname.replace("/dev/", "");
#endif
config->setName(QString("Serial Device on %1").arg(tname));
break;
}
#endif
case LinkConfiguration::TypeUdp:
config->setName(
QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
break;
case LinkConfiguration::TypeTcp: {
TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(config);
if(tconfig) {
config->setName(
QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port()));
}
}
break;
case LinkConfiguration::TypeBluetooth: {
BluetoothConfiguration* tconfig = dynamic_cast<BluetoothConfiguration*>(config);
if(tconfig) {
config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name));
case LinkConfiguration::TypeLogReplay: {
LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(config);
if(tconfig) {
config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort()));
}
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
config->setName(
QString("Mock Link"));
break;
#endif
case LinkConfiguration::TypeLast:
default:
break;
}
}
}
void LinkManager::removeConfiguration(LinkConfiguration* config)
{
Q_ASSERT(config != NULL);
LinkInterface* iface = config->link();
if(iface) {
disconnectLink(iface);
}
// Remove configuration
_linkConfigurations.removeOne(config);
delete config;
// Save list
saveLinkConfigurationList();
}
bool LinkManager::isAutoconnectLink(LinkInterface* link)
{
return _autoconnectConfigurations.contains(link->getLinkConfiguration());
}
bool LinkManager::isBluetoothAvailable(void)
{
return qgcApp()->isBluetoothAvailable();
}
bool found = false;
if (_activeLinkCheckList.count() != 0) {
link = _activeLinkCheckList.takeFirst();
if (_links.contains(link) && link->isConnected()) {
// Make sure there is a vehicle on the link
QmlObjectListModel* vehicles = _toolbox->multiVehicleManager()->vehicles();
for (int i=0; i<vehicles->count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles->get(i));
if (vehicle->containsLink(link)) {
found = true;
break;
}
}
}
}
if (_activeLinkCheckList.count() == 0) {
_activeLinkCheckTimer.stop();
}
if (!found && link) {
// See if we can get an NSH prompt on this link
bool foundNSHPrompt = false;
link->writeBytesSafe("\r", 1);
QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)));
if (spy.wait(100)) {
QList<QVariant> arguments = spy.takeFirst();
if (arguments[1].value<QByteArray>().contains("nsh>")) {
foundNSHPrompt = true;
}
}
qgcApp()->showMessage(foundNSHPrompt ?
QStringLiteral("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
QStringLiteral("Your Vehicle is not responding. If this continues shutdown QGroundControl, restart the Vehicle letting it boot completely, then start QGroundControl."));