Commit 73b18544 authored by Don Gagne's avatar Don Gagne

Merge pull request #2310 from DonLakeFlyer/ACFix

Change disconnect model for vehicles
parents c5c8871b 51b599a8
......@@ -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
......@@ -67,6 +67,8 @@ QGCView {
progressBar: progressBar
statusLog: statusTextArea
property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
Component.onCompleted: {
controllerCompleted = true
if (qgcView.completedSignalled) {
......@@ -75,20 +77,30 @@ QGCView {
}
}
onActiveVehicleChanged: {
if (!activeVehicle) {
statusTextArea.append(plugInText)
}
}
onNoBoardFound: {
initialBoardSearch = false
statusTextArea.append(plugInText)
if (!QGroundControl.multiVehicleManager.activeVehicleAvailable) {
statusTextArea.append(plugInText)
}
}
onBoardGone: {
initialBoardSearch = false
statusTextArea.append(plugInText)
if (!QGroundControl.multiVehicleManager.activeVehicleAvailable) {
statusTextArea.append(plugInText)
}
}
onBoardFound: {
if (initialBoardSearch) {
// Board was found right away, so something is already plugged in before we've started upgrade
if (QGroundControl.linkManager.anyActiveLinks) {
if (QGroundControl.multiVehicleManager.activeVehicleAvailable) {
statusTextArea.append(qgcDisconnectText)
} else {
statusTextArea.append(usbUnplugText.replace('{0}', controller.boardType))
......
......@@ -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 detect 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
};
......
This diff is collapsed.
......@@ -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,8 @@ private:
QmlObjectListModel _links;
QmlObjectListModel _linkConfigurations;
QmlObjectListModel _autoconnectConfigurations;
UDPConfiguration* _autoconnectUDPConfig;
QStringList _autoconnectWaitList;
bool _autoconnectUDP;
bool _autoconnectPixhawk;
......@@ -228,6 +218,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
......
......@@ -322,7 +322,7 @@ Row {
MenuItem {
checkable: true
checked: vehicle.active
checked: vehicle ? vehicle.active : false
onTriggered: multiVehicleManager.activeVehicle = vehicle
property int vehicleId: Number(text.split(" ")[1])
......@@ -360,6 +360,7 @@ Row {
//-- Mode Selector
Item {
id: flightModeSelector
width: selectorRow.width * 1.1
height: mainWindow.tbCellHeight
anchors.verticalCenter: parent.verticalCenter
......@@ -425,7 +426,7 @@ Row {
Connections {
target: multiVehicleManager
onActiveVehicleChanged: parent.updateFlightModesMenu
onActiveVehicleChanged: flightModeSelector.updateFlightModesMenu
}
MouseArea {
......
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