Unverified Commit d4bff450 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Param crash (#9124)

* Remove unneeded mutex

* Cleanup LinkInterface, fix connect/disconnect bug
parent e7d29a87
...@@ -83,6 +83,7 @@ ADSBTCPLink::ADSBTCPLink(const QString& hostAddress, int port, QObject* parent) ...@@ -83,6 +83,7 @@ ADSBTCPLink::ADSBTCPLink(const QString& hostAddress, int port, QObject* parent)
ADSBTCPLink::~ADSBTCPLink(void) ADSBTCPLink::~ADSBTCPLink(void)
{ {
if (_socket) { if (_socket) {
QObject::disconnect(_socket, &QTcpSocket::readyRead, this, &ADSBTCPLink::_readBytes);
_socket->disconnectFromHost(); _socket->disconnectFromHost();
_socket->deleteLater(); _socket->deleteLater();
_socket = nullptr; _socket = nullptr;
......
...@@ -390,8 +390,6 @@ void ParameterManager::_handleParamValue(int componentId, QString parameterName, ...@@ -390,8 +390,6 @@ void ParameterManager::_handleParamValue(int componentId, QString parameterName,
emit factAdded(componentId, fact); emit factAdded(componentId, fact);
} }
_dataMutex.unlock();
fact->_containerSetRawValue(parameterValue); fact->_containerSetRawValue(parameterValue);
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params // 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, ...@@ -416,8 +414,6 @@ void ParameterManager::_handleParamValue(int componentId, QString parameterName,
/// Writes the parameter update to mavlink, sets up for write wait /// 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) void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString& name, FactMetaData::ValueType_t valueType, const QVariant& rawValue)
{ {
_dataMutex.lock();
if (_waitingWriteParamNameMap.contains(componentId)) { if (_waitingWriteParamNameMap.contains(componentId)) {
if (_waitingWriteParamNameMap[componentId].contains(name)) { if (_waitingWriteParamNameMap[componentId].contains(name)) {
_waitingWriteParamNameMap[componentId].remove(name); _waitingWriteParamNameMap[componentId].remove(name);
...@@ -432,8 +428,6 @@ void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString& ...@@ -432,8 +428,6 @@ void ParameterManager::_factRawValueUpdateWorker(int componentId, const QString&
qWarning() << "Internal error ParameterManager::_factValueUpdateWorker: component id not found" << componentId; qWarning() << "Internal error ParameterManager::_factValueUpdateWorker: component id not found" << componentId;
} }
_dataMutex.unlock();
_sendParamSetToVehicle(componentId, name, valueType, rawValue); _sendParamSetToVehicle(componentId, name, valueType, rawValue);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Update parameter (_waitingParamTimeoutTimer started) - compId:name:rawValue" << componentId << name << 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) ...@@ -465,8 +459,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
emit missingParametersChanged(_missingParameters); emit missingParametersChanged(_missingParameters);
} }
_dataMutex.lock();
if (!_initialLoadComplete) { if (!_initialLoadComplete) {
_initialRequestTimeoutTimer.start(); _initialRequestTimeoutTimer.start();
} }
...@@ -482,8 +474,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) ...@@ -482,8 +474,6 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
} }
} }
_dataMutex.unlock();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg; mavlink_message_t msg;
...@@ -517,8 +507,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam ...@@ -517,8 +507,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam
componentId = _actualComponentId(componentId); componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")"; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
_dataMutex.lock();
if (_waitingReadParamNameMap.contains(componentId)) { if (_waitingReadParamNameMap.contains(componentId)) {
QString mappedParamName = _remapParamNameToVersion(paramName); QString mappedParamName = _remapParamNameToVersion(paramName);
...@@ -535,8 +523,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam ...@@ -535,8 +523,6 @@ void ParameterManager::refreshParameter(int componentId, const QString& paramNam
qWarning() << "Internal error"; qWarning() << "Internal error";
} }
_dataMutex.unlock();
_readParameterRaw(componentId, paramName, -1); _readParameterRaw(componentId, paramName, -1);
} }
......
...@@ -181,8 +181,6 @@ private: ...@@ -181,8 +181,6 @@ private:
QTimer _initialRequestTimeoutTimer; QTimer _initialRequestTimeoutTimer;
QTimer _waitingParamTimeoutTimer; QTimer _waitingParamTimeoutTimer;
QMutex _dataMutex;
Fact _defaultFact; ///< Used to return default fact, when parameter not found Fact _defaultFact; ///< Used to return default fact, when parameter not found
static const char* _jsonParametersKey; static const char* _jsonParametersKey;
......
...@@ -83,7 +83,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -83,7 +83,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
if (vehicleId != 81 || componentId != 50) { if (vehicleId != 81 || componentId != 50) {
// Don't create vehicles for components other than the autopilot // Don't create vehicles for components other than the autopilot
qCDebug(MultiVehicleManagerLog()) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType" qCDebug(MultiVehicleManagerLog()) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType"
<< link->getName() << link->linkConfiguration()->name()
<< vehicleId << vehicleId
<< componentId << componentId
<< vehicleFirmwareType << vehicleFirmwareType
...@@ -112,7 +112,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -112,7 +112,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
} }
qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType " qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType "
<< link->getName() << link->linkConfiguration()->name()
<< vehicleId << vehicleId
<< componentId << componentId
<< vehicleFirmwareType << vehicleFirmwareType
......
...@@ -171,7 +171,7 @@ void VehicleLinkManager::_addLink(LinkInterface* link) ...@@ -171,7 +171,7 @@ void VehicleLinkManager::_addLink(LinkInterface* link)
qCWarning(VehicleLinkManagerLog) << "_addLink call with link which is already in the list"; qCWarning(VehicleLinkManagerLog) << "_addLink call with link which is already in the list";
return; return;
} else { } 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(); link->addVehicleReference();
......
...@@ -47,11 +47,6 @@ void BluetoothLink::run() ...@@ -47,11 +47,6 @@ void BluetoothLink::run()
} }
QString BluetoothLink::getName() const
{
return _config->name();
}
void BluetoothLink::_writeBytes(const QByteArray bytes) void BluetoothLink::_writeBytes(const QByteArray bytes)
{ {
if (_targetSocket) { if (_targetSocket) {
...@@ -87,7 +82,7 @@ void BluetoothLink::disconnect(void) ...@@ -87,7 +82,7 @@ void BluetoothLink::disconnect(void)
#endif #endif
if(_targetSocket) { if(_targetSocket) {
// This prevents stale signals from calling the link after it has been deleted // 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->deleteLater();
_targetSocket = nullptr; _targetSocket = nullptr;
emit disconnected(); emit disconnected();
......
...@@ -129,9 +129,8 @@ public: ...@@ -129,9 +129,8 @@ public:
void run(void) override; void run(void) override;
// LinkConfiguration overrides // LinkConfiguration overrides
bool isConnected (void) const override; bool isConnected(void) const override;
QString getName (void) const override; void disconnect (void) override;
void disconnect (void) override;
public slots: public slots:
void readBytes (void); void readBytes (void);
......
...@@ -52,7 +52,6 @@ public: ...@@ -52,7 +52,6 @@ public:
SharedLinkConfigurationPtr linkConfiguration(void) { return _config; } SharedLinkConfigurationPtr linkConfiguration(void) { return _config; }
Q_INVOKABLE virtual QString getName (void) const = 0;
Q_INVOKABLE virtual void disconnect (void) = 0; Q_INVOKABLE virtual void disconnect (void) = 0;
virtual bool isConnected (void) const = 0; virtual bool isConnected (void) const = 0;
...@@ -70,7 +69,6 @@ signals: ...@@ -70,7 +69,6 @@ signals:
void bytesSent (LinkInterface* link, QByteArray data); void bytesSent (LinkInterface* link, QByteArray data);
void connected (void); void connected (void);
void disconnected (void); void disconnected (void);
void nameChanged (QString name);
void communicationError (const QString& title, const QString& error); void communicationError (const QString& title, const QString& error);
protected: protected:
......
...@@ -198,10 +198,15 @@ void LinkManager::_linkDisconnected(void) ...@@ -198,10 +198,15 @@ void LinkManager::_linkDisconnected(void)
return; 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()); _freeMavlinkChannel(link->mavlinkChannel());
for (int i=0; i<_rgLinks.count(); i++) { for (int i=0; i<_rgLinks.count(); i++) {
if (_rgLinks[i].get() == link) { 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); _rgLinks.removeAt(i);
return; return;
} }
......
...@@ -65,10 +65,9 @@ public: ...@@ -65,10 +65,9 @@ public:
void movePlayhead (qreal percentComplete); void movePlayhead (qreal percentComplete);
// overrides from LinkInterface // overrides from LinkInterface
QString getName (void) const override { return _config->name(); } bool isConnected(void) const override { return _connected; }
bool isConnected (void) const override { return _connected; } bool isLogReplay(void) override { return true; }
bool isLogReplay (void) override { return true; } void disconnect (void) override;
void disconnect (void) override;
public slots: public slots:
/// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X /// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X
......
...@@ -117,9 +117,8 @@ public: ...@@ -117,9 +117,8 @@ public:
MockLinkFTP* mockLinkFTP(void) { return _mockLinkFTP; } MockLinkFTP* mockLinkFTP(void) { return _mockLinkFTP; }
// Overrides from LinkInterface // Overrides from LinkInterface
QString getName (void) const override { return _name; } bool isConnected(void) const override { return _connected; }
bool isConnected (void) const override { return _connected; } void disconnect (void) override;
void disconnect (void) override;
/// Sets a failure mode for unit testingqgcm /// Sets a failure mode for unit testingqgcm
/// @param failureMode Type of failure to simulate /// @param failureMode Type of failure to simulate
......
...@@ -72,7 +72,7 @@ void SerialLink::_writeBytes(const QByteArray data) ...@@ -72,7 +72,7 @@ void SerialLink::_writeBytes(const QByteArray data)
} else { } else {
// Error occurred // Error occurred
qWarning() << "Serial port not writeable"; 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& ...@@ -202,7 +202,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString&
} }
#endif #endif
if (!_port->isOpen() ) { 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(); error = _port->error();
errorString = _port->errorString(); errorString = _port->errorString();
_port->close(); _port->close();
...@@ -241,7 +241,7 @@ void SerialLink::_readBytes(void) ...@@ -241,7 +241,7 @@ void SerialLink::_readBytes(void)
} else { } else {
// Error occurred // Error occurred
qWarning() << "Serial port not readable"; 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 ...@@ -275,16 +275,11 @@ bool SerialLink::isConnected() const
return isConnected; return isConnected;
} }
QString SerialLink::getName() const
{
return _serialConfig->name();
}
void SerialLink::_emitLinkError(const QString& errorMsg) void SerialLink::_emitLinkError(const QString& errorMsg)
{ {
QString msg("Error on link %1. %2"); QString msg("Error on link %1. %2");
qDebug() << errorMsg; qDebug() << errorMsg;
emit communicationError(tr("Link Error"), msg.arg(getName()).arg(errorMsg)); emit communicationError(tr("Link Error"), msg.arg(_config->name()).arg(errorMsg));
} }
//-------------------------------------------------------------------------- //--------------------------------------------------------------------------
......
...@@ -115,9 +115,8 @@ class SerialLink : public LinkInterface ...@@ -115,9 +115,8 @@ class SerialLink : public LinkInterface
public: public:
// LinkInterface overrides // LinkInterface overrides
QString getName (void) const override; bool isConnected(void) const override;
bool isConnected (void) const override; void disconnect (void) override;
void disconnect (void) override;
/// Don't even think of calling this method! /// Don't even think of calling this method!
QSerialPort* _hackAccessToPort(void) { return _port; } QSerialPort* _hackAccessToPort(void) { return _port; }
......
...@@ -107,7 +107,7 @@ void TCPLink::disconnect(void) ...@@ -107,7 +107,7 @@ void TCPLink::disconnect(void)
wait(); wait();
if (_socket) { if (_socket) {
// This prevents stale signal from calling the link after it has been deleted // 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; _socketIsConnected = false;
_socket->disconnectFromHost(); // Disconnect tcp _socket->disconnectFromHost(); // Disconnect tcp
_socket->waitForDisconnected(); _socket->waitForDisconnected();
...@@ -155,7 +155,7 @@ bool TCPLink::_hardwareConnect() ...@@ -155,7 +155,7 @@ bool TCPLink::_hardwareConnect()
// Whether a failed connection emits an error signal or not is platform specific. // 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. // So in cases where it is not emitted, we emit one ourselves.
if (errorSpy.count() == 0) { 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; delete _socket;
_socket = nullptr; _socket = nullptr;
...@@ -169,7 +169,7 @@ bool TCPLink::_hardwareConnect() ...@@ -169,7 +169,7 @@ bool TCPLink::_hardwareConnect()
void TCPLink::_socketError(QAbstractSocket::SocketError socketError) void TCPLink::_socketError(QAbstractSocket::SocketError socketError)
{ {
Q_UNUSED(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 ...@@ -182,11 +182,6 @@ bool TCPLink::isConnected() const
return _socketIsConnected; return _socketIsConnected;
} }
QString TCPLink::getName() const
{
return _tcpConfig->name();
}
void TCPLink::waitForBytesWritten(int msecs) void TCPLink::waitForBytesWritten(int msecs)
{ {
Q_ASSERT(_socket); Q_ASSERT(_socket);
......
...@@ -82,9 +82,8 @@ public: ...@@ -82,9 +82,8 @@ public:
void signalBytesWritten (void); void signalBytesWritten (void);
// LinkInterface overrides // LinkInterface overrides
QString getName (void) const override; bool isConnected(void) const override;
bool isConnected (void) const override; void disconnect (void) override;
void disconnect (void) override;
public slots: public slots:
void waitForBytesWritten(int msecs); void waitForBytesWritten(int msecs);
......
...@@ -112,11 +112,6 @@ void UDPLink::run() ...@@ -112,11 +112,6 @@ void UDPLink::run()
} }
} }
QString UDPLink::getName() const
{
return _udpConfig->name();
}
bool UDPLink::_isIpLocal(const QHostAddress& add) bool UDPLink::_isIpLocal(const QHostAddress& add)
{ {
// In simulation and testing setups the vehicle and the GCS can be // In simulation and testing setups the vehicle and the GCS can be
......
...@@ -105,9 +105,8 @@ public: ...@@ -105,9 +105,8 @@ public:
~UDPLink(); ~UDPLink();
// LinkInterface overrides // LinkInterface overrides
bool isConnected (void) const override; bool isConnected(void) const override;
QString getName (void) const override; void disconnect (void) override;
void disconnect (void) override;
// QThread overrides // QThread overrides
void run(void) override; void run(void) override;
......
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