Skip to content

Commit

Permalink
Revert "Comms: Update Serial Threading"
Browse files Browse the repository at this point in the history
This reverts commit 587887d.
  • Loading branch information
menschel committed Dec 16, 2024
1 parent 29b5b2b commit ec7b85d
Show file tree
Hide file tree
Showing 10 changed files with 452 additions and 496 deletions.
85 changes: 36 additions & 49 deletions android/libs/qtandroidserialport/qserialport_android.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@

#include <QtCore/QMap>
#include <QtCore/QThread>
#include <QtCore/QTimer>

#include <asm/termbits.h>

Expand Down Expand Up @@ -65,12 +64,6 @@ void QSerialPortPrivate::close()
{
qCDebug(AndroidSerialPortLog) << "Closing" << systemLocation.toLatin1().constData();

if (_readTimer) {
_readTimer->stop();
_readTimer->deleteLater();
_readTimer = nullptr;
}

if (_deviceId != INVALID_DEVICE_ID) {
if (!AndroidSerial::close(_deviceId)) {
qCWarning(AndroidSerialPortLog) << "Failed to close device with ID" << _deviceId;
Expand Down Expand Up @@ -100,39 +93,19 @@ bool QSerialPortPrivate::startAsyncRead()
setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to start async read")));
}

Q_Q(QSerialPort);
if (!_readTimer) {
_readTimer = new QTimer(q);
_readTimer->setInterval(EMIT_INTERVAL_MS);
(void) QObject::connect(_readTimer, &QTimer::timeout, q, [this]() {
Q_Q(QSerialPort);
QMutexLocker locker(&_readMutex);
if (!buffer.isEmpty()) {
emit q->readyRead();
}
});
_readTimer->start();
}

return result;
}

bool QSerialPortPrivate::_stopAsyncRead()
{
bool result = true;

if (AndroidSerial::readThreadRunning(_deviceId)) {
result = AndroidSerial::stopReadThread(_deviceId);
if (!result) {
qCWarning(AndroidSerialPortLog) << "Failed to stop async read thread for device ID" << _deviceId;
setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to stop async read")));
}
if (!AndroidSerial::readThreadRunning(_deviceId)) {
return true;
}

if (_readTimer) {
_readTimer->stop();
_readTimer->deleteLater();
_readTimer = nullptr;
const bool result = AndroidSerial::stopReadThread(_deviceId);
if (!result) {
qCWarning(AndroidSerialPortLog) << "Failed to stop async read thread for device ID" << _deviceId;
setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to stop async read")));
}

return result;
Expand All @@ -142,7 +115,7 @@ void QSerialPortPrivate::newDataArrived(const char *bytes, int length)
{
Q_Q(QSerialPort);

// qCDebug(AndroidSerialPortLog) << "newDataArrived" << length;
qCDebug(AndroidSerialPortLog) << "newDataArrived" << length;

QMutexLocker locker(&_readMutex);
int bytesToRead = length;
Expand All @@ -153,12 +126,18 @@ void QSerialPortPrivate::newDataArrived(const char *bytes, int length)
if (!_stopAsyncRead()) {
qCWarning(AndroidSerialPortLog) << "Failed to stop async read.";
}

return;
}
}

// qCDebug(AndroidSerialPortLog) << "nextDataBlockSize" << buffer.nextDataBlockSize();
(void) buffer.append(bytes, bytesToRead);
// const bool shouldSignal = buffer.isEmpty();

buffer.append(bytes, bytesToRead);

// TODO: Limit signals as one read can handle multiple signals
// if (shouldSignal)
emit q->readyRead();
_readWaitCondition.wakeAll();
}

Expand All @@ -169,17 +148,19 @@ bool QSerialPortPrivate::waitForReadyRead(int msecs)
return true;
}

QDeadlineTimer deadline(msecs);
QElapsedTimer timer;
timer.start();
while (buffer.isEmpty()) {
if (!_readWaitCondition.wait(&_readMutex, deadline)) {
break;
if (_readWaitCondition.wait(&_readMutex, msecs - static_cast<int>(timer.elapsed()))) {
if (!buffer.isEmpty()) {
return true;
}
}

if (!buffer.isEmpty()) {
return true;
if (timer.elapsed() >= msecs) {
break;
}
}
locker.unlock();

qCWarning(AndroidSerialPortLog) << "Timeout while waiting for ready read on device ID" << _deviceId;
setError(QSerialPortErrorInfo(QSerialPort::TimeoutError, QSerialPort::tr("Timeout while waiting for ready read")));
Expand All @@ -200,9 +181,7 @@ bool QSerialPortPrivate::waitForBytesWritten(int msecs)

bool QSerialPortPrivate::_writeDataOneShot(int msecs)
{
if (writeBuffer.isEmpty()) {
return true;
}
Q_Q(QSerialPort);

qint64 pendingBytesWritten = 0;

Expand All @@ -211,9 +190,10 @@ bool QSerialPortPrivate::_writeDataOneShot(int msecs)
const qint64 dataSize = writeBuffer.nextDataBlockSize();

const qint64 written = _writeToPort(dataPtr, dataSize, msecs);

if (written < 0) {
qCWarning(AndroidSerialPortLog) << "Failed to write data one shot on device ID" << _deviceId;
// setError(QSerialPortErrorInfo(QSerialPort::WriteError, QSerialPort::tr("Failed to write data one shot")));
setError(QSerialPortErrorInfo(QSerialPort::WriteError, QSerialPort::tr("Failed to write data one shot")));
return false;
}

Expand All @@ -223,7 +203,6 @@ bool QSerialPortPrivate::_writeDataOneShot(int msecs)

const bool result = (pendingBytesWritten > 0);
if (result) {
Q_Q(QSerialPort);
emit q->bytesWritten(pendingBytesWritten);
}

Expand All @@ -235,7 +214,7 @@ qint64 QSerialPortPrivate::_writeToPort(const char *data, qint64 maxSize, int ti
const qint64 result = AndroidSerial::write(_deviceId, data, maxSize, timeout, async);
if (result < 0) {
qCWarning(AndroidSerialPortLog) << "Failed to write to port ID" << _deviceId;
// setError(QSerialPortErrorInfo(QSerialPort::WriteError, QSerialPort::tr("Failed to write to port")));
setError(QSerialPortErrorInfo(QSerialPort::WriteError, QSerialPort::tr("Failed to write to port")));
}

return result;
Expand All @@ -259,7 +238,7 @@ qint64 QSerialPortPrivate::writeData(const char *data, qint64 maxSize)

bool QSerialPortPrivate::flush()
{
const bool result = _writeDataOneShot();
const bool result = _writeDataOneShot(0);
if (!result) {
qCWarning(AndroidSerialPortLog) << "Flush operation failed for device ID" << _deviceId;
setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to flush")));
Expand Down Expand Up @@ -291,6 +270,14 @@ bool QSerialPortPrivate::clear(QSerialPort::Directions directions)
// setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to purge buffers")));
}

/*if (input) {
buffer.clear();
}
if (output) {
writeBuffer.clear();
}*/

return result;
}

Expand Down
7 changes: 1 addition & 6 deletions android/libs/qtandroidserialport/qserialport_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,11 @@ constexpr qint64 DEFAULT_READ_BUFFER_SIZE = MAX_READ_SIZE;
constexpr qint64 DEFAULT_WRITE_BUFFER_SIZE = 16 * 1024;
constexpr int DEFAULT_WRITE_TIMEOUT = 0;
constexpr int DEFAULT_READ_TIMEOUT = 0;
constexpr int EMIT_THRESHOLD = 64;
constexpr int EMIT_INTERVAL_MS = 10;

#ifndef QSERIALPORT_BUFFERSIZE
#define QSERIALPORT_BUFFERSIZE DEFAULT_WRITE_BUFFER_SIZE
#endif

class QTimer;

Q_DECLARE_LOGGING_CATEGORY(AndroidSerialPortLog)

QT_BEGIN_NAMESPACE
Expand Down Expand Up @@ -136,7 +132,7 @@ class QSerialPortPrivate : public QIODevicePrivate
qint64 _writeToPort(const char *data, qint64 maxSize, int timeout = DEFAULT_WRITE_TIMEOUT, bool async = false);
bool _stopAsyncRead();
bool _setParameters(qint32 baudRate, QSerialPort::DataBits dataBits, QSerialPort::StopBits stopBits, QSerialPort::Parity parity);
bool _writeDataOneShot(int msecs = DEFAULT_WRITE_TIMEOUT);
bool _writeDataOneShot(int msecs);

static qint32 _settingFromBaudRate(qint32 baudRate);
static int _stopBitsToAndroidStopBits(QSerialPort::StopBits stopBits);
Expand All @@ -147,7 +143,6 @@ class QSerialPortPrivate : public QIODevicePrivate
int _deviceId = INVALID_DEVICE_ID;
// QString _serialNumber;

QTimer *_readTimer = nullptr;
QMutex _readMutex;
QWaitCondition _readWaitCondition;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,6 @@ public void onReceive(Context context, Intent intent) {
break;
}

updateCurrentDrivers();

try {
nativeUpdateAvailableJoysticks();
} catch (final Exception ex) {
Expand Down Expand Up @@ -411,7 +409,7 @@ private static UsbSerialPort findPortByDeviceId(final int deviceId) {
* @return An array of device information strings or null if no devices are available.
*/
public static String[] availableDevicesInfo() {
// updateCurrentDrivers();
updateCurrentDrivers();

if (usbManager.getDeviceList().size() < 1) {
return null;
Expand Down
2 changes: 1 addition & 1 deletion src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void)
// FIXME: Put back
for (const QVariant& varLink: _vehicle->links()) {
SerialLink* serialLink = varLink.value<SerialLink*>();
if (serialLink && QSerialPortInfo(*serialLink->port()).description().contains(QStringLiteral("CubeBlack"))) {
if (serialLink && QSerialPortInfo(*serialLink->_hackAccessToPort()).description().contains(QStringLiteral("CubeBlack"))) {
cubeBlackFound = true;
}

Expand Down
2 changes: 1 addition & 1 deletion src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -945,7 +945,7 @@ void LinkManager::_updateSerialPorts()
for (const QGCSerialPortInfo &info: portList) {
const QString port = info.systemLocation().trimmed();
_commPortList += port;
_commPortDisplayList += SerialConfiguration::cleanPortDisplayName(port);
_commPortDisplayList += SerialConfiguration::cleanPortDisplayname(port);
}
}

Expand Down
3 changes: 3 additions & 0 deletions src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,9 @@ class LinkManager : public QObject
void loadLinkConfigurationList();
void saveLinkConfigurationList();

/// Suspend automatic confguration updates (during link maintenance for instance)
void suspendConfigurationUpdates(bool suspend) { _configUpdateSuspended = suspend; }

/// Sets the flag to suspend the all new connections
/// @param reason User visible reason to suspend connections
void setConnectionsSuspended(const QString &reason) { _connectionsSuspended = true; _connectionsSuspendedReason = reason; }
Expand Down
30 changes: 11 additions & 19 deletions src/Comms/QGCSerialPortInfo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ bool QGCSerialPortInfo::_loadJsonData()

QString errorString;
int version;
const QJsonObject json = JsonHelper::openInternalQGCJsonFile(QStringLiteral(":/json/USBBoardInfo.json"), QString(_jsonFileTypeValue), 1, 1, version, errorString);
const QJsonObject json = JsonHelper::openInternalQGCJsonFile(":/json/USBBoardInfo.json", _jsonFileTypeValue, 1, 1, version, errorString);
if (!errorString.isEmpty()) {
qCWarning(QGCSerialPortInfoLog) << "Internal Error:" << errorString;
return false;
Expand Down Expand Up @@ -165,14 +165,7 @@ bool QGCSerialPortInfo::_loadJsonData()

QGCSerialPortInfo::BoardType_t QGCSerialPortInfo::_boardClassStringToType(const QString &boardClass)
{
static const BoardClassString2BoardType_t rgBoardClass2BoardType[BoardTypeUnknown] = {
{ _boardTypeToString(BoardTypePixhawk), BoardTypePixhawk },
{ _boardTypeToString(BoardTypeRTKGPS), BoardTypeRTKGPS },
{ _boardTypeToString(BoardTypeSiKRadio), BoardTypeSiKRadio },
{ _boardTypeToString(BoardTypeOpenPilot), BoardTypeOpenPilot },
};

for (const BoardClassString2BoardType_t &board : rgBoardClass2BoardType) {
for (const BoardClassString2BoardType_t &board : _rgBoardClass2BoardType) {
if (boardClass == board.classString) {
return board.boardType;
}
Expand Down Expand Up @@ -252,14 +245,12 @@ QString QGCSerialPortInfo::_boardTypeToString(BoardType_t boardType)
QList<QGCSerialPortInfo> QGCSerialPortInfo::availablePorts()
{
QList<QGCSerialPortInfo> list;

const QList<QSerialPortInfo> availablePorts = QSerialPortInfo::availablePorts();
for (const QSerialPortInfo &portInfo : availablePorts) {
for (const QSerialPortInfo &portInfo : QSerialPortInfo::availablePorts()) {
if (isSystemPort(portInfo)) {
continue;
}

const QGCSerialPortInfo *const qgcPortInfo = reinterpret_cast<const QGCSerialPortInfo*>(&portInfo);
const QGCSerialPortInfo* const qgcPortInfo = reinterpret_cast<const QGCSerialPortInfo*>(&portInfo);
list << *qgcPortInfo;
}

Expand Down Expand Up @@ -307,10 +298,11 @@ bool QGCSerialPortInfo::canFlash() const
return false;
}

static const QList<BoardType_t> flashable = {
BoardTypePixhawk,
BoardTypeSiKRadio
};

return flashable.contains(boardType);
switch(boardType) {
case QGCSerialPortInfo::BoardTypePixhawk:
case QGCSerialPortInfo::BoardTypeSiKRadio:
return true;
default:
return false;
}
}
19 changes: 12 additions & 7 deletions src/Comms/QGCSerialPortInfo.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,12 @@ class QGCSerialPortInfo : public QSerialPortInfo
~QGCSerialPortInfo();

enum BoardType_t {
BoardTypePixhawk = 0,
BoardTypePixhawk,
BoardTypeSiKRadio,
BoardTypeOpenPilot,
BoardTypeRTKGPS,
BoardTypeUnknown
};

bool getBoardInfo(BoardType_t &boardType, QString &name) const;

/// @return true: we can flash this board type
Expand All @@ -56,18 +55,24 @@ class QGCSerialPortInfo : public QSerialPortInfo
static QList<QGCSerialPortInfo> availablePorts();

private:
struct BoardClassString2BoardType_t {
const QString classString;
const BoardType_t boardType = BoardTypeUnknown;
};

static bool _loadJsonData();
static BoardType_t _boardClassStringToType(const QString &boardClass);
static QString _boardTypeToString(BoardType_t boardType);

static bool _jsonLoaded;
static bool _jsonDataValid;

struct BoardClassString2BoardType_t {
const char *classString;
BoardType_t boardType;
};
static constexpr const BoardClassString2BoardType_t _rgBoardClass2BoardType[BoardTypeUnknown] = {
{ "Pixhawk", QGCSerialPortInfo::BoardTypePixhawk },
{ "RTK GPS", QGCSerialPortInfo::BoardTypeRTKGPS },
{ "SiK Radio", QGCSerialPortInfo::BoardTypeSiKRadio },
{ "OpenPilot", QGCSerialPortInfo::BoardTypeOpenPilot },
};

struct BoardInfo_t {
int vendorId;
int productId;
Expand Down
Loading

0 comments on commit ec7b85d

Please sign in to comment.