Skip to content

Commit

Permalink
Android: Serial Fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Aug 20, 2024
1 parent 8a9f99e commit 247b1a8
Show file tree
Hide file tree
Showing 12 changed files with 335 additions and 713 deletions.
24 changes: 11 additions & 13 deletions android/AndroidManifest.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,19 +13,21 @@

<!-- %%INSERT_PERMISSIONS -->

<!-- Need MulticastLock to receive broadcast UDP packets -->
<uses-permission android:name="android.permission.CHANGE_WIFI_MULTICAST_STATE" />
<!-- Needed to keep working while 'asleep' -->
<uses-permission android:name="android.permission.WAKE_LOCK"/>
<!-- Need MulticastLock to receive broadcast UDP packets -->
<uses-permission android:name="android.permission.CHANGE_WIFI_MULTICAST_STATE"/>
<uses-permission android:name="android.permission.WAKE_LOCK" />

<!-- %%INSERT_FEATURES -->

<uses-feature android:name="android.hardware.usb.host" android:required="false"/>
<uses-feature android:name="android.hardware.usb.accessory" android:required="false"/>
<uses-feature android:name="android.hardware.bluetooth" android:required="false"/>
<uses-feature android:name="android.hardware.location.gps" android:required="false"/>
<uses-feature android:name="android.hardware.location.network" android:required="false"/>
<uses-feature android:name="android.hardware.location" android:required="false"/>
<uses-feature android:name="android.hardware.audio.output" android:required="false" />
<uses-feature android:name="android.hardware.bluetooth" android:required="false" />
<uses-feature android:name="android.hardware.camera.any" android:required="false" />
<uses-feature android:name="android.hardware.location" android:required="false" />
<uses-feature android:name="android.hardware.location.gps" android:required="false" />
<uses-feature android:name="android.hardware.location.network" android:required="false" />
<uses-feature android:name="android.hardware.usb.host" android:required="false" />
<uses-feature android:name="android.hardware.wifi" android:required="false" />

<application
android:name="org.qtproject.qt.android.bindings.QtApplication"
Expand Down Expand Up @@ -56,7 +58,6 @@
<intent-filter>
<action android:name="android.hardware.usb.action.USB_DEVICE_ATTACHED" />
<action android:name="android.hardware.usb.action.USB_DEVICE_DETACHED" />
<action android:name="android.hardware.usb.action.USB_ACCESSORY_ATTACHED" />
<action android:name="android.bluetooth.device.action.ACL_CONNECTED" />
<action android:name="android.bluetooth.device.action.ACL_DISCONNECTED" />
<!-- TODO: CMake configure xml file -->
Expand All @@ -70,9 +71,6 @@
<meta-data
android:name="android.hardware.usb.action.USB_DEVICE_DETACHED"
android:resource="@xml/device_filter" />
<meta-data
android:name="android.hardware.usb.action.USB_ACCESSORY_ATTACHED"
android:resource="@xml/device_filter" />

<meta-data
android:name="android.app.lib_name"
Expand Down
1 change: 1 addition & 0 deletions android/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ android {
// versionName "5.0"
// versionCode 5

// println "applicationId: ${applicationId}"
println "minSdkVersion: ${minSdkVersion}"
println "targetSdkVersion: ${targetSdkVersion}"
println "ndk.abiFilters: ${ndk.abiFilters}"
Expand Down
36 changes: 19 additions & 17 deletions android/libs/qtandroidserialport/qserialport_android.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,12 @@ bool QSerialPortPrivate::open(QIODevice::OpenMode mode)
return false;
}

/*if (mode & QIODevice::ReadOnly) {
if (mode & QIODevice::ReadOnly) {
// readBufferMaxSize = AndroidSerial::getReadBufferSize();
startAsyncRead();
}

if (!clear(QSerialPort::AllDirections)) {
/*if (!clear(QSerialPort::AllDirections)) {
close();
return false;
}*/
Expand Down Expand Up @@ -82,12 +82,12 @@ bool QSerialPortPrivate::startAsyncRead()

void QSerialPortPrivate::newDataArrived(char *bytes, int length)
{
if (!q_func()->isOpen()) {
Q_Q(QSerialPort);

if (!q->isOpen()) {
return;
}

Q_Q(QSerialPort);

int bytesToRead = length;
if (readBufferMaxSize && (bytesToRead > (readBufferMaxSize - buffer.size()))) {
bytesToRead = static_cast<int>(readBufferMaxSize - buffer.size());
Expand All @@ -97,7 +97,7 @@ void QSerialPortPrivate::newDataArrived(char *bytes, int length)
}
}

char * const ptr = buffer.reserve(bytesToRead);
char* const ptr = buffer.reserve(bytesToRead);
(void) memcpy(ptr, bytes, static_cast<size_t>(bytesToRead));

emit q->readyRead();
Expand All @@ -110,7 +110,7 @@ void QSerialPortPrivate::exceptionArrived(const QString &ex)

bool QSerialPortPrivate::waitForReadyRead(int msecs)
{
const int orig = static_cast<int>(buffer.size());
const qint64 orig = static_cast<int>(buffer.size());

if (orig > 0) {
return true;
Expand All @@ -129,20 +129,21 @@ bool QSerialPortPrivate::waitForReadyRead(int msecs)

bool QSerialPortPrivate::waitForBytesWritten(int msecs)
{
m_internalWriteTimeoutMsec = msecs;
const bool ret = _writeDataOneShot();
m_internalWriteTimeoutMsec = 0;
return ret;
// if (writeBuffer.isEmpty() && (m_pendingBytesWritten <= 0)) {
// return false;
// }

return _writeDataOneShot(msecs);
}

bool QSerialPortPrivate::_writeDataOneShot()
bool QSerialPortPrivate::_writeDataOneShot(int msecs)
{
Q_Q(QSerialPort);

m_pendingBytesWritten = -1;

while (!writeBuffer.isEmpty()) {
m_pendingBytesWritten = writeToPort(writeBuffer.readPointer(), writeBuffer.nextDataBlockSize());
m_pendingBytesWritten = _writeToPort(writeBuffer.readPointer(), writeBuffer.nextDataBlockSize(), msecs, false);

if (m_pendingBytesWritten <= 0) {
setError(QSerialPortErrorInfo(QSerialPort::WriteError));
Expand All @@ -157,19 +158,20 @@ bool QSerialPortPrivate::_writeDataOneShot()
return (m_pendingBytesWritten >= 0);
}

qint64 QSerialPortPrivate::writeToPort(const char *data, qint64 maxSize)
qint64 QSerialPortPrivate::_writeToPort(const char *data, qint64 maxSize, int timeout, bool async)
{
return AndroidSerial::write(m_deviceId, data, maxSize, m_internalWriteTimeoutMsec, false);
return AndroidSerial::write(m_deviceId, data, maxSize, timeout, async);
}

qint64 QSerialPortPrivate::writeData(const char *data, qint64 maxSize)
{
return writeToPort(data, maxSize);
(void) writeBuffer.append(data, maxSize);
return _writeDataOneShot(0);
}

bool QSerialPortPrivate::flush()
{
return _writeDataOneShot();
return _writeDataOneShot(0);
}

bool QSerialPortPrivate::clear(QSerialPort::Directions directions)
Expand Down
7 changes: 2 additions & 5 deletions android/libs/qtandroidserialport/qserialport_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,6 @@ class QSerialPortPrivate : public QIODevicePrivate
bool startAsyncRead();

qint64 writeData(const char *data, qint64 maxSize);
qint64 writeToPort(const char *data, qint64 maxSize);

void newDataArrived(char *bytes, int length);
void exceptionArrived(const QString &ex);
Expand All @@ -123,21 +122,19 @@ class QSerialPortPrivate : public QIODevicePrivate
int descriptor = -1;

private:
qint64 _writeToPort(const char *data, qint64 maxSize, int timeout = 0, bool async = false);
bool _stopAsyncRead();
bool _setParameters(int baudRate, int dataBits, int stopBits, int parity);
bool _writeDataOneShot();
bool _writeDataOneShot(int msecs);

static qint32 _settingFromBaudRate(qint32 baudRate);

// bool m_settingsRestoredOnClose = true;

qint64 m_pendingBytesWritten = 0;

int m_deviceId = BAD_PORT;
int m_dataBits = AndroidSerial::Data8;
int m_stopBits = AndroidSerial::OneStop;
int m_parity = AndroidSerial::NoParity;
qint64 m_internalWriteTimeoutMsec = 0;
};

QT_END_NAMESPACE
Expand Down
9 changes: 4 additions & 5 deletions android/src/AndroidInit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ extern "C"
}
#endif

static void jniInit(JNIEnv* env, jobject context)
static void jniInit(JNIEnv *env, jobject context)
{
qCDebug(AndroidInitLog) << Q_FUNC_INFO;

Expand All @@ -52,8 +52,7 @@ static jint jniSetNativeMethods()
{
qCDebug(AndroidInitLog) << Q_FUNC_INFO;

const JNINativeMethod javaMethods[]
{
const JNINativeMethod javaMethods[] {
{"nativeInit", "()V", reinterpret_cast<void *>(jniInit)}
};

Expand All @@ -78,13 +77,13 @@ static jint jniSetNativeMethods()
return JNI_OK;
}

jint JNI_OnLoad(JavaVM* vm, void* reserved)
jint JNI_OnLoad(JavaVM *vm, void *reserved)
{
Q_UNUSED(reserved);

qCDebug(AndroidInitLog) << Q_FUNC_INFO;

JNIEnv* env;
JNIEnv *env;
if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK) {
return JNI_ERR;
}
Expand Down
4 changes: 3 additions & 1 deletion android/src/AndroidInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -135,9 +135,11 @@ jclass getActivityClass()
qCWarning(AndroidInterfaceLog) << "Class Not Found";
return nullptr;
}

env.checkAndClearExceptions();
}

return javaClass;
}

} // namespace AndroidInterface
} // namespace AndroidInterface
65 changes: 24 additions & 41 deletions android/src/AndroidSerial.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,42 +47,42 @@ void setNativeMethods()
(void) jniEnv.checkAndClearExceptions();
}

void jniDeviceHasDisconnected(JNIEnv *env, jobject obj, jlong userData)
void jniDeviceHasDisconnected(JNIEnv *env, jobject obj, jlong classPtr)
{
Q_UNUSED(env);
Q_UNUSED(obj);

if (userData != 0) {
QSerialPortPrivate* const serialPortPrivate = reinterpret_cast<QSerialPortPrivate*>(userData);
qCDebug(AndroidSerialLog) << "Device disconnected" << serialPortPrivate->systemLocation.toLatin1().data();
if (classPtr != 0) {
QSerialPortPrivate* const serialPortPrivate = reinterpret_cast<QSerialPortPrivate*>(classPtr);
qCDebug(AndroidSerialLog) << "Device disconnected" << serialPortPrivate->systemLocation.toLatin1().constData();
QSerialPort* const serialPort = static_cast<QSerialPort*>(serialPortPrivate->q_ptr);
serialPort->close();
}
}

void jniDeviceNewData(JNIEnv *env, jobject obj, jlong userData, jbyteArray data)
void jniDeviceNewData(JNIEnv *env, jobject obj, jlong classPtr, jbyteArray data)
{
Q_UNUSED(obj);

if (userData != 0) {
if (classPtr != 0) {
jbyte* const bytes = env->GetByteArrayElements(data, nullptr);
const jsize len = env->GetArrayLength(data);
// QByteArray data = QByteArray::fromRawData(reinterpret_cast<char*>(bytes), len);
QSerialPortPrivate* const serialPort = reinterpret_cast<QSerialPortPrivate*>(userData);
QSerialPortPrivate* const serialPort = reinterpret_cast<QSerialPortPrivate*>(classPtr);
serialPort->newDataArrived(reinterpret_cast<char*>(bytes), len);
env->ReleaseByteArrayElements(data, bytes, JNI_ABORT);
(void) QJniEnvironment::checkAndClearExceptions(env);
}
}

void jniDeviceException(JNIEnv *env, jobject obj, jlong userData, jstring message)
void jniDeviceException(JNIEnv *env, jobject obj, jlong classPtr, jstring message)
{
Q_UNUSED(obj);

if (userData != 0) {
if (classPtr != 0) {
const char* const string = env->GetStringUTFChars(message, nullptr);
const QString str = QString::fromUtf8(string);
QSerialPortPrivate* const serialPort = reinterpret_cast<QSerialPortPrivate*>(userData);
QSerialPortPrivate* const serialPort = reinterpret_cast<QSerialPortPrivate*>(classPtr);
serialPort->exceptionArrived(str);
env->ReleaseStringUTFChars(message, string);
(void) QJniEnvironment::checkAndClearExceptions(env);
Expand Down Expand Up @@ -125,22 +125,22 @@ QList<QSerialPortInfo> availableDevices()
env->ReleaseStringUTFChars(string, rawString);
env->DeleteLocalRef(string);

if (strList.size() < 4) {
if (strList.size() < 6) {
qCWarning(AndroidSerialLog) << "Invalid device info";
continue;
}

QSerialPortInfoPrivate priv;

priv.portName = strList.at(0);
priv.device = strList.at(0);
priv.description = "";
priv.manufacturer = strList.at(1);
priv.serialNumber = ""; // getSerialNumber(getDeviceId(priv.portName));
priv.productIdentifier = strList.at(2).toInt();
priv.portName = QSerialPortInfoPrivate::portNameFromSystemLocation(strList.at(0));
priv.device = strList.at(0);
priv.description = strList.at(1);
priv.manufacturer = strList.at(2);
priv.serialNumber = strList.at(3);
priv.productIdentifier = strList.at(4).toInt();
priv.hasProductIdentifier = (priv.productIdentifier != BAD_PORT);
priv.vendorIdentifier = strList.at(3).toInt();
priv.hasVendorIdentifier = (priv.vendorIdentifier != BAD_PORT);
priv.vendorIdentifier = strList.at(5).toInt();
priv.hasVendorIdentifier = (priv.vendorIdentifier != BAD_PORT);

(void) serialPortInfoList.append(priv);
}
Expand All @@ -149,25 +149,6 @@ QList<QSerialPortInfo> availableDevices()
return serialPortInfoList;
}

QString getSerialNumber(int deviceId)
{
(void) AndroidInterface::cleanJavaException();
const QJniObject result = QJniObject::callStaticMethod<jobject>(
AndroidInterface::getActivityClass(),
"getSerialNumber",
"(I)Ljava/lang/String;",
deviceId
);
(void) AndroidInterface::cleanJavaException();

if (!result.isValid()) {
qCWarning(AndroidSerialLog) << "Invalid Result";
return QString();
}

return result.toString();
}

int getDeviceId(const QString &portName)
{
QJniObject name = QJniObject::fromString(portName);
Expand Down Expand Up @@ -198,7 +179,7 @@ int getDeviceHandle(int deviceId)
return result;
}

int open(const QString &portName, QSerialPortPrivate *userData)
int open(const QString &portName, QSerialPortPrivate *classPtr)
{
QJniObject name = QJniObject::fromString(portName);

Expand All @@ -209,7 +190,7 @@ int open(const QString &portName, QSerialPortPrivate *userData)
"(Landroid/content/Context;Ljava/lang/String;J)I",
QNativeInterface::QAndroidApplication::context(),
name.object<jstring>(),
reinterpret_cast<jlong>(userData)
reinterpret_cast<jlong>(classPtr)
);
(void) AndroidInterface::cleanJavaException();

Expand Down Expand Up @@ -277,14 +258,16 @@ int write(int deviceId, QByteArrayView data, int length, int timeout, bool async
jniEnv->SetByteArrayRegion(jarray, 0, static_cast<jsize>(length), reinterpret_cast<const jbyte*>(data.constData()));

(void) jniEnv.checkAndClearExceptions();
timeout = qMax(0, timeout);
int result;
if (async) {
result = QJniObject::callStaticMethod<jint>(
AndroidInterface::getActivityClass(),
"writeAsync",
"(I[B)V",
deviceId,
jarray
jarray,
timeout
);
} else {
result = QJniObject::callStaticMethod<jint>(
Expand Down
Loading

0 comments on commit 247b1a8

Please sign in to comment.