Commit ca6eccda authored by Don Gagne's avatar Don Gagne

Autoconnect restructuring

Windows OS doesn’t disconnect port when you pull plug on USB. This
caused all sorts of problems with previous logic. New logic handles
this correctly.
parent 13cc3b12
......@@ -138,7 +138,7 @@ void AirframeComponentController::_rebootAfterStackUnwind(void)
QGC::SLEEP::usleep(500);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
qgcApp()->toolbox()->linkManager()->disconnectAll(false /* disconnectAutoconnectLink */);
qgcApp()->toolbox()->linkManager()->disconnectAll();
qgcApp()->restoreOverrideCursor();
}
......
......@@ -228,8 +228,6 @@ Item {
QGCMapPalette { id: mapPal; lightColors: !isBackgroundDark }
Component.onCompleted: console.log("test", mapPal)
MultiPointTouchArea {
anchors.fill: parent
touchPoints: [
......@@ -254,7 +252,6 @@ Item {
var point1
if (touchPoints.length > 0) {
//console.log("Point1", touchPoints[0].x, touchPoints[0].y)
point1 = touchPoints[0]
if (pointInRect(leftRect, point1)) {
point1Location = -1
......@@ -265,7 +262,6 @@ Item {
var point2
if (touchPoints.length == 2) {
//console.log("Point2", touchPoints[1].x, touchPoints[1].y)
point2 = touchPoints[1]
if (pointInRect(leftRect, point2)) {
point2Location = -1
......
......@@ -81,7 +81,7 @@ void QGroundControlQmlGlobal::_startMockLink(MockConfiguration* mockConfig)
mockConfig->setDynamic(true);
linkManager->linkConfigurations()->append(mockConfig);
linkManager->createConnectedLink(mockConfig, false /* autoconnectLink */);
linkManager->createConnectedLink(mockConfig);
}
#endif
......@@ -155,7 +155,7 @@ void QGroundControlQmlGlobal::stopAllMockLinks(void)
MockLink* mockLink = qobject_cast<MockLink*>(link);
if (mockLink) {
linkManager->disconnectLink(mockLink, false /* disconnectAutoconnectLink */);
linkManager->disconnectLink(mockLink);
}
}
#endif
......
......@@ -44,7 +44,6 @@ QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
const char* Vehicle::_settingsGroup = "Vehicle%1"; // %1 replaced with mavlink system id
const char* Vehicle::_joystickModeSettingsKey = "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey = "JoystickEnabled";
const char* Vehicle::_communicationInactivityKey = "CommunicationInactivity";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
......@@ -102,7 +101,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _communicationInactivityTimeoutMSecs(_communicationInactivityTimeoutMSecsDefault)
, _firmwarePluginManager(firmwarePluginManager)
, _autopilotPluginManager(autopilotPluginManager)
, _joystickManager(joystickManager)
......@@ -182,10 +180,6 @@ Vehicle::Vehicle(LinkInterface* link,
_mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
_communicationInactivityTimer.setInterval(_communicationInactivityTimeoutMSecs);
connect(&_communicationInactivityTimer, &QTimer::timeout, this, &Vehicle::_communicationInactivityTimedOut);
_communicationInactivityTimer.start();
}
Vehicle::~Vehicle()
......@@ -209,8 +203,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
return;
}
_communicationInactivityTimer.start();
if (!_containsLink(link)) {
_addLink(link);
}
......@@ -311,6 +303,7 @@ void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
_links.removeOne(link);
if (_links.count() == 0 && !_allLinksInactiveSent) {
qCDebug(VehicleLog) << "All links inactive";
// Make sure to not send this more than one time
_allLinksInactiveSent = true;
emit allLinksInactive(this);
......@@ -771,7 +764,6 @@ void Vehicle::_loadSettings(void)
}
_joystickEnabled = settings.value(_joystickEnabledSettingsKey, false).toBool();
_communicationInactivityTimeoutMSecs = settings.value(_communicationInactivityKey, _communicationInactivityTimeoutMSecsDefault).toInt();
}
void Vehicle::_saveSettings(void)
......@@ -782,7 +774,6 @@ void Vehicle::_saveSettings(void)
settings.setValue(_joystickModeSettingsKey, _joystickMode);
settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
settings.setValue(_communicationInactivityKey, _communicationInactivityTimeoutMSecs);
}
int Vehicle::joystickMode(void)
......@@ -1035,13 +1026,13 @@ void Vehicle::_parametersReady(bool parametersReady)
}
}
void Vehicle::_communicationInactivityTimedOut(void)
void Vehicle::disconnectInactiveVehicle(void)
{
// Vehicle is no longer communicating with us, disconnect all links inactive
// Vehicle is no longer communicating with us, disconnect all links
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
for (int i=0; i<_links.count(); i++) {
linkMgr->disconnectLink(_links[i], false /* disconnectAutoconnectLink */);
linkMgr->disconnectLink(_links[i]);
}
}
......
......@@ -125,6 +125,7 @@ public:
Q_INVOKABLE void resetMessages();
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Q_INVOKABLE void disconnectInactiveVehicle(void);
// Property accessors
......@@ -311,7 +312,6 @@ private slots:
void _sendMessageMultipleNext(void);
void _addNewMapTrajectoryPoint(void);
void _parametersReady(bool parametersReady);
void _communicationInactivityTimedOut(void);
void _remoteControlRSSIChanged(uint8_t rssi);
void _handleTextMessage (int newCount);
......@@ -436,10 +436,6 @@ private:
bool _mapTrajectoryHaveFirstCoordinate;
static const int _mapTrajectoryMsecsBetweenPoints = 1000;
QTimer _communicationInactivityTimer;
int _communicationInactivityTimeoutMSecs;
static const int _communicationInactivityTimeoutMSecsDefault = 30 * 1000;
FirmwarePluginManager* _firmwarePluginManager;
AutoPilotPluginManager* _autopilotPluginManager;
JoystickManager* _joystickManager;
......@@ -452,6 +448,5 @@ private:
static const char* _settingsGroup;
static const char* _joystickModeSettingsKey;
static const char* _joystickEnabledSettingsKey;
static const char* _communicationInactivityKey;
};
#endif
......@@ -159,7 +159,7 @@ Rectangle {
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
font.pixelSize: ScreenTools.largeFontPixelSize
text: "Click Connect on the top right to Fly. Click Firmware on the left to upgrade your vehicle."
text: "Connect vehicle to your device and QGroundControl will automatically connect to it. Click Firmware on the left to upgrade your vehicle."
onLinkActivated: Qt.openUrlExternally(link)
}
......
......@@ -57,12 +57,9 @@ class LinkInterface : public QThread
friend class LinkManager;
public:
Q_PROPERTY(bool autoconnect READ autoconnect WRITE setAutoconnect NOTIFY autoconnectChanged)
Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
// Property accessors
bool autoconnect(void) { return _autoconnect; }
void setAutoconnect(bool autoconnect) { _autoconnect = autoconnect; emit autoconnectChanged(autoconnect); }
bool active(void) { return _active; }
void setActive(bool active) { _active = active; emit activeChanged(active); }
......@@ -198,7 +195,6 @@ protected:
LinkInterface() :
QThread(0)
, _mavlinkChannelSet(false)
, _autoconnect(false)
, _active(false)
{
// Initialize everything for the data rate calculation buffers.
......@@ -361,7 +357,6 @@ private:
mutable QMutex _dataRateMutex; // Mutex for accessing the data rate member variables
bool _autoconnect; ///< true: Link is an autoconnect connection and should never be disconnected
bool _active; ///< true: link is actively receiving mavlink messages
};
......
......@@ -53,6 +53,7 @@ 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";
LinkManager::LinkManager(QGCApplication* app)
: QGCTool(app)
......@@ -61,7 +62,6 @@ LinkManager::LinkManager(QGCApplication* app)
, _connectionsSuspended(false)
, _mavlinkChannelsUsedBitMask(0)
, _mavlinkProtocol(NULL)
, _autoconnectUDPConfig(NULL)
, _autoconnectUDP(true)
, _autoconnectPixhawk(true)
, _autoconnect3DRRadio(true)
......@@ -100,7 +100,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
}
LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config, bool autoconnectLink)
LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config)
{
Q_ASSERT(config);
LinkInterface* pLink = NULL;
......@@ -126,20 +126,19 @@ LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config, bool
#endif
}
if(pLink) {
pLink->setAutoconnect(autoconnectLink);
_addLink(pLink);
connectLink(pLink);
}
return pLink;
}
LinkInterface* LinkManager::createConnectedLink(const QString& name, bool autoconnectLink)
LinkInterface* LinkManager::createConnectedLink(const QString& name)
{
Q_ASSERT(name.isEmpty() == false);
for(int i = 0; i < _linkConfigurations.count(); i++) {
LinkConfiguration* conf = _linkConfigurations.value<LinkConfiguration*>(i);
if(conf && conf->name() == name)
return createConnectedLink(conf, autoconnectLink);
return createConnectedLink(conf);
}
return NULL;
}
......@@ -184,11 +183,11 @@ void LinkManager::_addLink(LinkInterface* link)
connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
}
void LinkManager::disconnectAll(bool disconnectAutoconnectLink)
void LinkManager::disconnectAll(void)
{
// Walk list in reverse order to preserve indices during delete
for (int i=_links.count()-1; i>=0; i--) {
disconnectLink(_links.value<LinkInterface*>(i), disconnectAutoconnectLink);
disconnectLink(_links.value<LinkInterface*>(i));
}
}
......@@ -201,36 +200,27 @@ bool LinkManager::connectLink(LinkInterface* link)
}
bool previousAnyConnectedLinks = anyConnectedLinks();
bool previousAnyNonAutoconnectConnectedLinks = anyNonAutoconnectConnectedLinks();
if (link->_connect()) {
if (!previousAnyConnectedLinks) {
emit anyConnectedLinksChanged(true);
}
if (!previousAnyNonAutoconnectConnectedLinks && anyNonAutoconnectConnectedLinks()) {
emit anyNonAutoconnectConnectedLinksChanged(true);
}
return true;
} else {
return false;
}
}
bool LinkManager::disconnectLink(LinkInterface* link, bool disconnectAutoconnectLink)
void LinkManager::disconnectLink(LinkInterface* link)
{
Q_ASSERT(link);
if (disconnectAutoconnectLink || !link->autoconnect()) {
link->_disconnect();
LinkConfiguration* config = link->getLinkConfiguration();
if(config) {
config->setLink(NULL);
}
_deleteLink(link);
return true;
link->_disconnect();
LinkConfiguration* config = link->getLinkConfiguration();
if(config) {
config->setLink(NULL);
}
return false;
_deleteLink(link);
}
void LinkManager::_deleteLink(LinkInterface* link)
......@@ -420,14 +410,23 @@ void LinkManager::_updateAutoConnectLinks(void)
return;
}
if (_autoconnectUDP && !_autoconnectUDPConfig) {
_autoconnectUDPConfig = new UDPConfiguration("Default UDP Link");
_autoconnectUDPConfig->setLocalPort(QGC_UDP_LOCAL_PORT);
_autoconnectUDPConfig->setDynamic(true);
createConnectedLink(_autoconnectUDPConfig, true /* persistenLink */);
// 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;
}
}
if (!foundUDP) {
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT);
udpConfig->setDynamic(true);
createConnectedLink(udpConfig);
}
#ifndef __ios__
QStringList currentPorts;
QList<QGCSerialPortInfo> portList = QGCSerialPortInfo::availablePorts();
......@@ -492,7 +491,7 @@ void LinkManager::_updateAutoConnectLinks(void)
_autoconnectConfigurations.append(pSerialConfig);
createConnectedLink(pSerialConfig, true /* persistenLink */);
createConnectedLink(pSerialConfig);
}
}
}
......@@ -505,19 +504,22 @@ void LinkManager::_updateAutoConnectLinks(void)
if (linkConfig) {
if (!currentPorts.contains(linkConfig->portName())) {
_confToDelete.append(linkConfig);
// We don't remove links which are still connected even though at this point the cable may
// have been pulled. This is due to the fact that whether a serial port goes away from the
// list when the cable is pulled is OS dependant. By not disconnecting in this case, we keep
// things working the same across all OS.
if (!linkConfig->link() || !linkConfig->link()->isConnected()) {
_confToDelete.append(linkConfig);
}
}
} else {
qWarning() << "Internal error";
}
}
// Now disconnect/remove all links that are gone
// Now remove all configs that are gone
foreach (LinkConfiguration* pDeleteConfig, _confToDelete) {
LinkInterface* link = pDeleteConfig->link();
if (link) {
disconnectLink(link, true /* disconnectAutoconnectLink */);
}
qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name();
_autoconnectConfigurations.removeOne(pDeleteConfig);
delete pDeleteConfig;
}
......@@ -538,21 +540,6 @@ bool LinkManager::anyConnectedLinks(void)
return found;
}
bool LinkManager::anyNonAutoconnectConnectedLinks(void)
{
// FIXME: Should remove this duplication with anyConnectedLinks
bool found = false;
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links.value<LinkInterface*>(i);
if (link && !link->autoconnect() && link->isConnected()) {
found = true;
break;
}
}
return found;
}
bool LinkManager::anyActiveLinks(void)
{
bool found = false;
......@@ -567,21 +554,6 @@ bool LinkManager::anyActiveLinks(void)
return found;
}
bool LinkManager::anyNonAutoconnectActiveLinks(void)
{
// FIXME: Should remove this duplication with anyActiveLinks
bool found = false;
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links.value<LinkInterface*>(i);
if (link && !link->autoconnect() && link->active()) {
found = true;
break;
}
}
return found;
}
void LinkManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType)
{
if (!link->active() && !_ignoreVehicleIds.contains(vehicleId)) {
......@@ -607,7 +579,6 @@ void LinkManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int
}
bool previousAnyActiveLinks = anyActiveLinks();
bool previousAnyNonAutoconnectActiveLinks = anyNonAutoconnectActiveLinks();
link->setActive(true);
emit linkActive(link, vehicleId, vehicleFirmwareType, vehicleType);
......@@ -615,16 +586,13 @@ void LinkManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int
if (!previousAnyActiveLinks) {
emit anyActiveLinksChanged(true);
}
if (!previousAnyNonAutoconnectActiveLinks && anyNonAutoconnectActiveLinks()) {
emit anyNonAutoconnectActiveLinksChanged(true);
}
}
}
void LinkManager::shutdown(void)
{
setConnectionsSuspended("Shutdown");
disconnectAll(true /* disconnectAutoconnectLink */);
disconnectAll();
}
void LinkManager::setAutoconnectUDP(bool autoconnect)
......
......@@ -73,9 +73,7 @@ public:
~LinkManager();
Q_PROPERTY(bool anyActiveLinks READ anyActiveLinks NOTIFY anyActiveLinksChanged)
Q_PROPERTY(bool anyNonAutoconnectActiveLinks READ anyNonAutoconnectActiveLinks NOTIFY anyNonAutoconnectActiveLinksChanged)
Q_PROPERTY(bool anyConnectedLinks READ anyConnectedLinks NOTIFY anyConnectedLinksChanged)
Q_PROPERTY(bool anyNonAutoconnectConnectedLinks READ anyNonAutoconnectConnectedLinks NOTIFY anyNonAutoconnectConnectedLinksChanged)
Q_PROPERTY(bool autoconnectUDP READ autoconnectUDP WRITE setAutoconnectUDP NOTIFY autoconnectUDPChanged)
Q_PROPERTY(bool autoconnectPixhawk READ autoconnectPixhawk WRITE setAutoconnectPixhawk NOTIFY autoconnectPixhawkChanged)
Q_PROPERTY(bool autoconnect3DRRadio READ autoconnect3DRRadio WRITE setAutoconnect3DRRadio NOTIFY autoconnect3DRRadioChanged)
......@@ -88,9 +86,7 @@ public:
// Property accessors
bool anyConnectedLinks(void);
bool anyNonAutoconnectConnectedLinks(void);
bool anyActiveLinks(void);
bool anyNonAutoconnectActiveLinks(void);
bool autoconnectUDP(void) { return _autoconnectUDP; }
bool autoconnectPixhawk(void) { return _autoconnectPixhawk; }
bool autoconnect3DRRadio(void) { return _autoconnect3DRRadio; }
......@@ -123,24 +119,19 @@ public:
/// Creates, connects (and adds) a link based on the given configuration instance.
/// Link takes ownership of config.
Q_INVOKABLE LinkInterface* createConnectedLink(LinkConfiguration* config, bool persistenLink = false);
Q_INVOKABLE LinkInterface* createConnectedLink(LinkConfiguration* config);
/// Creates, connects (and adds) a link based on the given configuration name.
LinkInterface* createConnectedLink(const QString& name, bool persistenLink = false);
LinkInterface* createConnectedLink(const QString& name);
/// Disconnects all existing links, including persistent links.
/// @param disconnectAutoconnectLink See disconnectLink
void disconnectAll(bool disconnectAutoconnectLink);
/// Disconnects all existing links
void disconnectAll(void);
/// Connect the specified link
bool connectLink(LinkInterface* link);
/// Disconnect the specified link.
/// @param disconnectAutoconnectLink
/// true: link is disconnected no matter what type
/// false: if autoconnect link, link is marked as inactive and linkInactive is signalled
/// false: if not autoconnect link, link is disconnected
Q_INVOKABLE bool disconnectLink(LinkInterface* link, bool disconnectAutoconnectLink);
/// Disconnect the specified link
Q_INVOKABLE void disconnectLink(LinkInterface* link);
/// Called to notify that a heartbeat was received with the specified information. Will transition
/// a link to active as needed.
......@@ -163,9 +154,7 @@ public:
signals:
void anyActiveLinksChanged(bool anyActiveLinks);
void anyNonAutoconnectActiveLinksChanged(bool anyNonAutoconnectActiveLinks);
void anyConnectedLinksChanged(bool anyConnectedLinks);
void anyNonAutoconnectConnectedLinksChanged(bool anyNoAutoconnectConnectedLinks);
void autoconnectUDPChanged(bool autoconnect);
void autoconnectPixhawkChanged(bool autoconnect);
void autoconnect3DRRadioChanged(bool autoconnect);
......@@ -216,7 +205,6 @@ private:
QmlObjectListModel _links;
QmlObjectListModel _linkConfigurations;
QmlObjectListModel _autoconnectConfigurations;
UDPConfiguration* _autoconnectUDPConfig;
bool _autoconnectUDP;
bool _autoconnectPixhawk;
......@@ -228,6 +216,7 @@ private:
static const char* _autoconnectPixhawkKey;
static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey;
static const char* _defaultUPDLinkName;
};
#endif
......@@ -211,9 +211,6 @@ bool SerialLink::_hardwareConnect(QString &type)
return false; // couldn't create serial port.
}
// We need to catch this signal and then emit disconnected. You can't connect
// signal to signal otherwise disonnected will have the wrong QObject::Sender
QObject::connect(_port, SIGNAL(aboutToClose()), this, SLOT(_rerouteDisconnected()));
QObject::connect(_port, SIGNAL(error(QSerialPort::SerialPortError)), this, SLOT(linkError(QSerialPort::SerialPortError)));
QObject::connect(_port, &QIODevice::readyRead, this, &SerialLink::_readBytes);
......@@ -361,11 +358,6 @@ void SerialLink::_resetConfiguration()
}
}
void SerialLink::_rerouteDisconnected(void)
{
emit disconnected();
}
void SerialLink::_emitLinkError(const QString& errorMsg)
{
QString msg("Error on link %1. %2");
......
......@@ -150,7 +150,6 @@ protected:
QString _type;
private slots:
void _rerouteDisconnected(void);
void _readBytes(void);
private:
......
......@@ -387,7 +387,7 @@ void UnitTest::_disconnectMockLink(void)
if (_mockLink) {
QSignalSpy linkSpy(_linkManager, SIGNAL(linkDeleted(LinkInterface*)));
_linkManager->disconnectLink(_mockLink, false /* disconnectAutoconnectLink */);
_linkManager->disconnectLink(_mockLink);
// Wait for link to go away
linkSpy.wait(1000);
......
......@@ -73,7 +73,7 @@ void QGCLinkConfiguration::on_delLinkButton_clicked()
// Get link attached to this configuration (if any)
LinkInterface* iface = config->link();
if(iface) {
qgcApp()->toolbox()->linkManager()->disconnectLink(iface, false /* disconnectAutoconnectLink */);
qgcApp()->toolbox()->linkManager()->disconnectLink(iface);
}
_viewModel->beginChange();
......@@ -106,7 +106,7 @@ void QGCLinkConfiguration::on_connectLinkButton_clicked()
if(link) {
// Disconnect Link
if (link->isConnected()) {
qgcApp()->toolbox()->linkManager()->disconnectLink(link, false /* disconnectAutoconnectLink */);
qgcApp()->toolbox()->linkManager()->disconnectLink(link);
}
} else {
LinkInterface* link = qgcApp()->toolbox()->linkManager()->createConnectedLink(config);
......
......@@ -152,10 +152,6 @@ Rectangle {
toolBarMessageArea.visible = true
}
function showMavStatus() {
return (multiVehicleManager.activeVehicleAvailable && activeVehicle.heartbeatTimeout === 0);
}
function getBatteryColor() {
if(activeVehicle) {
if(activeVehicle.batteryPercent > 75) {
......@@ -554,29 +550,40 @@ Rectangle {
Item {
id: vehicleIndicators
visible: showMavStatus() && !connectionStatus.visible
height: mainWindow.tbCellHeight
width: (toolBar.width - viewRow.width)
anchors.left: viewRow.right
anchors.leftMargin: mainWindow.tbSpacing * 2
anchors.left: viewRow.right
anchors.right: parent.right
anchors.verticalCenter: parent.verticalCenter
property bool vehicleInactive: activeVehicle ? activeVehicle.heartbeatTimeout != 0 : false
Loader {
source: multiVehicleManager.activeVehicleAvailable ? "MainToolBarIndicators.qml" : ""
anchors.left: parent.left
anchors.verticalCenter: parent.verticalCenter
source: activeVehicle && !parent.vehicleInactive ? "MainToolBarIndicators.qml" : ""
anchors.left: parent.left
anchors.verticalCenter: parent.verticalCenter
}
}
QGCLabel {
id: connectionStatus
visible: (_controller.connectionCount > 0 && multiVehicleManager.activeVehicleAvailable && activeVehicle.heartbeatTimeout != 0)
text: "CONNECTION LOST"
font.pixelSize: tbFontLarge
font.weight: Font.DemiBold
color: colorRed
anchors.left: viewRow.right
anchors.leftMargin: mainWindow.tbSpacing * 2
anchors.verticalCenter: parent.verticalCenter
QGCLabel {
id: connectionLost
text: "CONNECTION LOST"
font.pixelSize: tbFontLarge
font.weight: Font.DemiBold
color: colorRed
anchors.left: parent.left
anchors.verticalCenter: parent.verticalCenter
visible: parent.vehicleInactive
}
QGCButton {
anchors.rightMargin: mainWindow.tbSpacing * 2
anchors.right: parent.right
anchors.verticalCenter: parent.verticalCenter
text: "Disconnect"
visible: parent.vehicleInactive
onClicked: activeVehicle.disconnectInactiveVehicle()
}
}
// Progress bar
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment