From d4bff450fccfc83e8b1f07232dc52c2bbc249a82 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 19 Oct 2020 15:38:55 -0700 Subject: [PATCH] Param crash (#9124) * Remove unneeded mutex * Cleanup LinkInterface, fix connect/disconnect bug --- src/ADSB/ADSBVehicleManager.cc | 1 + src/FactSystem/ParameterManager.cc | 14 -------------- src/FactSystem/ParameterManager.h | 2 -- src/Vehicle/MultiVehicleManager.cc | 4 ++-- src/Vehicle/VehicleLinkManager.cc | 2 +- src/comm/BluetoothLink.cc | 7 +------ src/comm/BluetoothLink.h | 5 ++--- src/comm/LinkInterface.h | 2 -- src/comm/LinkManager.cc | 7 ++++++- src/comm/LogReplayLink.h | 7 +++---- src/comm/MockLink.h | 5 ++--- src/comm/SerialLink.cc | 13 ++++--------- src/comm/SerialLink.h | 5 ++--- src/comm/TCPLink.cc | 11 +++-------- src/comm/TCPLink.h | 5 ++--- src/comm/UDPLink.cc | 5 ----- src/comm/UDPLink.h | 5 ++--- 17 files changed, 31 insertions(+), 69 deletions(-) diff --git a/src/ADSB/ADSBVehicleManager.cc b/src/ADSB/ADSBVehicleManager.cc index c905aef85..3d03f8f3f 100644 --- a/src/ADSB/ADSBVehicleManager.cc +++ b/src/ADSB/ADSBVehicleManager.cc @@ -83,6 +83,7 @@ ADSBTCPLink::ADSBTCPLink(const QString& hostAddress, int port, QObject* parent) ADSBTCPLink::~ADSBTCPLink(void) { if (_socket) { + QObject::disconnect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes); _socket->disconnectFromHost(); _socket->deleteLater(); _socket = nullptr; diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 7c3f2290b..d28d31c52 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -390,8 +390,6 @@ void ParameterManager::_handleParamValue(int componentId, QString parameterName, emit factAdded(componentId, fact); } - _dataMutex.unlock(); - fact->_containerSetRawValue(parameterValue); // Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params @@ -416,8 +414,6 @@ void ParameterManager::_handleParamValue(int componentId, QString parameterName, /// Writes the parameter update to mavlink, sets up for write wait void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString& name, FactMetaData::ValueType_t valueType, const QVariant& rawValue) { - _dataMutex.lock(); - if (_waitingWriteParamNameMap.contains(componentId)) { if (_waitingWriteParamNameMap[componentId].contains(name)) { _waitingWriteParamNameMap[componentId].remove(name); @@ -432,8 +428,6 @@ void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString& qWarning() << "Internal error ParameterManager::_factValueUpdateWorker: component id not found" << componentId; } - _dataMutex.unlock(); - _sendParamSetToVehicle(componentId, name, valueType, rawValue); qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Update parameter (_waitingParamTimeoutTimer started) - compId:name:rawValue" << componentId << name << rawValue; } @@ -465,8 +459,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) emit missingParametersChanged(_missingParameters); } - _dataMutex.lock(); - if (!_initialLoadComplete) { _initialRequestTimeoutTimer.start(); } @@ -482,8 +474,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) } } - _dataMutex.unlock(); - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_message_t msg; @@ -517,8 +507,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam componentId = _actualComponentId(componentId); qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")"; - _dataMutex.lock(); - if (_waitingReadParamNameMap.contains(componentId)) { QString mappedParamName = _remapParamNameToVersion(paramName); @@ -535,8 +523,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam qWarning() << "Internal error"; } - _dataMutex.unlock(); - _readParameterRaw(componentId, paramName, -1); } diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index 67d20df68..fb06129f8 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -181,8 +181,6 @@ private: QTimer _initialRequestTimeoutTimer; QTimer _waitingParamTimeoutTimer; - QMutex _dataMutex; - Fact _defaultFact; ///< Used to return default fact, when parameter not found static const char* _jsonParametersKey; diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index 0c5a47de2..e7eefef58 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -83,7 +83,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle if (vehicleId != 81 || componentId != 50) { // Don't create vehicles for components other than the autopilot qCDebug(MultiVehicleManagerLog()) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType" - << link->getName() + << link->linkConfiguration()->name() << vehicleId << componentId << vehicleFirmwareType @@ -112,7 +112,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle } qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType " - << link->getName() + << link->linkConfiguration()->name() << vehicleId << componentId << vehicleFirmwareType diff --git a/src/Vehicle/VehicleLinkManager.cc b/src/Vehicle/VehicleLinkManager.cc index be4c98209..d12b2fcf0 100644 --- a/src/Vehicle/VehicleLinkManager.cc +++ b/src/Vehicle/VehicleLinkManager.cc @@ -171,7 +171,7 @@ void VehicleLinkManager::_addLink(LinkInterface* link) qCWarning(VehicleLinkManagerLog) << "_addLink call with link which is already in the list"; return; } else { - qCDebug(VehicleLinkManagerLog) << "_addLink:" << link->getName() << QString("%1").arg((qulonglong)link, 0, 16); + qCDebug(VehicleLinkManagerLog) << "_addLink:" << link->linkConfiguration()->name() << QString("%1").arg((qulonglong)link, 0, 16); link->addVehicleReference(); diff --git a/src/comm/BluetoothLink.cc b/src/comm/BluetoothLink.cc index ede027ed6..0770a7112 100644 --- a/src/comm/BluetoothLink.cc +++ b/src/comm/BluetoothLink.cc @@ -47,11 +47,6 @@ void BluetoothLink::run() } -QString BluetoothLink::getName() const -{ - return _config->name(); -} - void BluetoothLink::_writeBytes(const QByteArray bytes) { if (_targetSocket) { @@ -87,7 +82,7 @@ void BluetoothLink::disconnect(void) #endif if(_targetSocket) { // This prevents stale signals from calling the link after it has been deleted - QObject::connect(_targetSocket, &QBluetoothSocket::readyRead, this, &BluetoothLink::readBytes); + QObject::disconnect(_targetSocket, &QBluetoothSocket::readyRead, this, &BluetoothLink::readBytes); _targetSocket->deleteLater(); _targetSocket = nullptr; emit disconnected(); diff --git a/src/comm/BluetoothLink.h b/src/comm/BluetoothLink.h index 3cea7a249..114e1d2e6 100644 --- a/src/comm/BluetoothLink.h +++ b/src/comm/BluetoothLink.h @@ -129,9 +129,8 @@ public: void run(void) override; // LinkConfiguration overrides - bool isConnected (void) const override; - QString getName (void) const override; - void disconnect (void) override; + bool isConnected(void) const override; + void disconnect (void) override; public slots: void readBytes (void); diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index a9d153227..32aae5911 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -52,7 +52,6 @@ public: SharedLinkConfigurationPtr linkConfiguration(void) { return _config; } - Q_INVOKABLE virtual QString getName (void) const = 0; Q_INVOKABLE virtual void disconnect (void) = 0; virtual bool isConnected (void) const = 0; @@ -70,7 +69,6 @@ signals: void bytesSent (LinkInterface* link, QByteArray data); void connected (void); void disconnected (void); - void nameChanged (QString name); void communicationError (const QString& title, const QString& error); protected: diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index d8641a6f5..87a59075a 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -198,10 +198,15 @@ void LinkManager::_linkDisconnected(void) return; } + disconnect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); + disconnect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); + disconnect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes); + disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected); + _freeMavlinkChannel(link->mavlinkChannel()); for (int i=0; i<_rgLinks.count(); i++) { if (_rgLinks[i].get() == link) { - qCDebug(LinkManagerLog) << "LinkManager::_linkDisconnected" <<_rgLinks[i]->getName() << _rgLinks[i].use_count(); + qCDebug(LinkManagerLog) << "LinkManager::_linkDisconnected" << _rgLinks[i]->linkConfiguration()->name() << _rgLinks[i].use_count(); _rgLinks.removeAt(i); return; } diff --git a/src/comm/LogReplayLink.h b/src/comm/LogReplayLink.h index 70258335e..f5b2a60d2 100644 --- a/src/comm/LogReplayLink.h +++ b/src/comm/LogReplayLink.h @@ -65,10 +65,9 @@ public: void movePlayhead (qreal percentComplete); // overrides from LinkInterface - QString getName (void) const override { return _config->name(); } - bool isConnected (void) const override { return _connected; } - bool isLogReplay (void) override { return true; } - void disconnect (void) override; + bool isConnected(void) const override { return _connected; } + bool isLogReplay(void) override { return true; } + void disconnect (void) override; public slots: /// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h index ef86a6b14..7d778a961 100644 --- a/src/comm/MockLink.h +++ b/src/comm/MockLink.h @@ -117,9 +117,8 @@ public: MockLinkFTP* mockLinkFTP(void) { return _mockLinkFTP; } // Overrides from LinkInterface - QString getName (void) const override { return _name; } - bool isConnected (void) const override { return _connected; } - void disconnect (void) override; + bool isConnected(void) const override { return _connected; } + void disconnect (void) override; /// Sets a failure mode for unit testingqgcm /// @param failureMode Type of failure to simulate diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 3ed29fd9f..ca523ef2e 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -72,7 +72,7 @@ void SerialLink::_writeBytes(const QByteArray data) } else { // Error occurred qWarning() << "Serial port not writeable"; - _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName())); + _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(_config->name())); } } @@ -202,7 +202,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& } #endif if (!_port->isOpen() ) { - qDebug() << "open failed" << _port->errorString() << _port->error() << getName() << "autconnect:" << _config->isAutoConnect(); + qDebug() << "open failed" << _port->errorString() << _port->error() << _config->name() << "autconnect:" << _config->isAutoConnect(); error = _port->error(); errorString = _port->errorString(); _port->close(); @@ -241,7 +241,7 @@ void SerialLink::_readBytes(void) } else { // Error occurred qWarning() << "Serial port not readable"; - _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(getName())); + _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(_config->name())); } } @@ -275,16 +275,11 @@ bool SerialLink::isConnected() const return isConnected; } -QString SerialLink::getName() const -{ - return _serialConfig->name(); -} - void SerialLink::_emitLinkError(const QString& errorMsg) { QString msg("Error on link %1. %2"); qDebug() << errorMsg; - emit communicationError(tr("Link Error"), msg.arg(getName()).arg(errorMsg)); + emit communicationError(tr("Link Error"), msg.arg(_config->name()).arg(errorMsg)); } //-------------------------------------------------------------------------- diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index b931d42c0..b62758cf5 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -115,9 +115,8 @@ class SerialLink : public LinkInterface public: // LinkInterface overrides - QString getName (void) const override; - bool isConnected (void) const override; - void disconnect (void) override; + bool isConnected(void) const override; + void disconnect (void) override; /// Don't even think of calling this method! QSerialPort* _hackAccessToPort(void) { return _port; } diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 12cd5c049..7d98c2ed1 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -107,7 +107,7 @@ void TCPLink::disconnect(void) wait(); if (_socket) { // This prevents stale signal from calling the link after it has been deleted - QObject::connect(_socket, &QTcpSocket::readyRead, this, &TCPLink::readBytes); + QObject::disconnect(_socket, &QTcpSocket::readyRead, this, &TCPLink::readBytes); _socketIsConnected = false; _socket->disconnectFromHost(); // Disconnect tcp _socket->waitForDisconnected(); @@ -155,7 +155,7 @@ bool TCPLink::_hardwareConnect() // Whether a failed connection emits an error signal or not is platform specific. // So in cases where it is not emitted, we emit one ourselves. if (errorSpy.count() == 0) { - emit communicationError(tr("Link Error"), tr("Error on link %1. Connection failed").arg(getName())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Connection failed").arg(_config->name())); } delete _socket; _socket = nullptr; @@ -169,7 +169,7 @@ bool TCPLink::_hardwareConnect() void TCPLink::_socketError(QAbstractSocket::SocketError socketError) { Q_UNUSED(socketError); - emit communicationError(tr("Link Error"), tr("Error on link %1. Error on socket: %2.").arg(getName()).arg(_socket->errorString())); + emit communicationError(tr("Link Error"), tr("Error on link %1. Error on socket: %2.").arg(_config->name()).arg(_socket->errorString())); } /** @@ -182,11 +182,6 @@ bool TCPLink::isConnected() const return _socketIsConnected; } -QString TCPLink::getName() const -{ - return _tcpConfig->name(); -} - void TCPLink::waitForBytesWritten(int msecs) { Q_ASSERT(_socket); diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h index b404eac38..543a4956f 100644 --- a/src/comm/TCPLink.h +++ b/src/comm/TCPLink.h @@ -82,9 +82,8 @@ public: void signalBytesWritten (void); // LinkInterface overrides - QString getName (void) const override; - bool isConnected (void) const override; - void disconnect (void) override; + bool isConnected(void) const override; + void disconnect (void) override; public slots: void waitForBytesWritten(int msecs); diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 4c14e916e..c81ab4e3d 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -112,11 +112,6 @@ void UDPLink::run() } } -QString UDPLink::getName() const -{ - return _udpConfig->name(); -} - bool UDPLink::_isIpLocal(const QHostAddress& add) { // In simulation and testing setups the vehicle and the GCS can be diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index 459d05be6..97f47fea0 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -105,9 +105,8 @@ public: ~UDPLink(); // LinkInterface overrides - bool isConnected (void) const override; - QString getName (void) const override; - void disconnect (void) override; + bool isConnected(void) const override; + void disconnect (void) override; // QThread overrides void run(void) override; -- 2.22.0