QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
AndroidSerial.cc
Go to the documentation of this file.
1#include "AndroidSerial.h"
2
3#include <QtCore/QHash>
4#include <QtCore/QJniEnvironment>
5#include <QtCore/QJniObject>
6#include <QtCore/QMutex>
7#include <QtCore/QPointer>
8#include <QtCore/QRandomGenerator>
9#include <QtCore/QReadWriteLock>
10#include <QtCore/QThread>
11#include <qserialport_p.h>
12#include <qserialportinfo_p.h>
13
14#include <utility>
15
16#include "AndroidInterface.h"
17#include "QGCLoggingCategory.h"
18
19QGC_LOGGING_CATEGORY(AndroidSerialLog, "Android.AndroidSerial");
20
21namespace AndroidSerial {
22
23// ----------------------------------------------------------------------------
24// Token-based pointer tracking (UAF protection)
25//
26// Java receives an opaque random jlong token instead of a raw C++ pointer.
27// A bidirectional hash map under QReadWriteLock maps tokens ↔ pointers.
28// JNI callbacks (readers) take a shared read lock; register/unregister
29// (writers) take an exclusive write lock. Pattern follows Qt Bluetooth's
30// LowEnergyNotificationHub.
31// ----------------------------------------------------------------------------
32
33static QReadWriteLock s_ptrLock;
34static QHash<jlong, QSerialPortPrivate*> s_tokenToPtr;
35static QHash<QSerialPortPrivate*, jlong> s_ptrToToken;
36
38{
39 if (!ptr) {
40 qCWarning(AndroidSerialLog) << "registerPointer called with null pointer";
41 return;
42 }
43
44 QWriteLocker locker(&s_ptrLock);
45
46 const auto existingIt = s_ptrToToken.constFind(ptr);
47 if (existingIt != s_ptrToToken.cend()) {
48 s_tokenToPtr.remove(*existingIt);
49 s_ptrToToken.erase(existingIt);
50 }
51
52 jlong token;
53 do {
54 token = static_cast<jlong>(QRandomGenerator::global()->generate64());
55 } while (token == 0 || s_tokenToPtr.contains(token));
56
57 s_tokenToPtr.insert(token, ptr);
58 s_ptrToToken.insert(ptr, token);
59}
60
62{
63 if (!ptr) {
64 return;
65 }
66
67 QWriteLocker locker(&s_ptrLock);
68 const jlong token = s_ptrToToken.take(ptr);
69 if (token == 0) {
70 return;
71 }
72 s_tokenToPtr.remove(token);
73}
74
76{
77 QReadLocker locker(&s_ptrLock);
78 return s_tokenToPtr.value(token, nullptr);
79}
80
82{
83 QReadLocker locker(&s_ptrLock);
84 return s_ptrToToken.value(ptr, 0);
85}
86
88{
89 QSerialPortPrivate* const serialPortPrivate = s_tokenToPtr.value(token, nullptr);
90 if (!serialPortPrivate) {
91 return nullptr;
92 }
93
94 return qobject_cast<QSerialPort*>(serialPortPrivate->q_ptr);
95}
96
97template <typename Functor>
98static bool dispatchToPortObject(QSerialPort* serialPort, Functor&& func, const char* context)
99{
100 if (!serialPort) {
101 qCWarning(AndroidSerialLog) << context << ": null serial port";
102 return false;
103 }
104
105 QThread* const targetThread = serialPort->thread();
106 const bool sameThread = (targetThread == QThread::currentThread());
107 const bool hasEventLoop = targetThread && targetThread->eventDispatcher();
108
109 if (sameThread) {
110 std::forward<Functor>(func)();
111 return true;
112 }
113
114 if (hasEventLoop) {
115 // BlockingQueuedConnection ensures the operation completes on the target thread
116 // before returning to the JNI caller (e.g. device disconnect is fully processed
117 // before Java-side cleanup continues).
118 const bool ok = QMetaObject::invokeMethod(serialPort, std::forward<Functor>(func), Qt::BlockingQueuedConnection);
119 if (!ok) {
120 qCWarning(AndroidSerialLog) << context << ": failed to invoke method on target thread";
121 }
122 return ok;
123 }
124
125 qCWarning(AndroidSerialLog) << context << ": target thread has no event loop, running inline fallback";
126 std::forward<Functor>(func)();
127 return true;
128}
129
130// ----------------------------------------------------------------------------
131// JNI method ID cache
132// ----------------------------------------------------------------------------
133
135{
136 jmethodID availableDevicesInfo = nullptr;
137 jmethodID getDeviceId = nullptr;
138 jmethodID getDeviceHandle = nullptr;
139 jmethodID open = nullptr;
140 jmethodID close = nullptr;
141 jmethodID isDeviceNameOpen = nullptr;
142 jmethodID read = nullptr;
143 jmethodID write = nullptr;
144 jmethodID writeAsync = nullptr;
145 jmethodID setParameters = nullptr;
146 jmethodID getCarrierDetect = nullptr;
147 jmethodID getClearToSend = nullptr;
148 jmethodID getDataSetReady = nullptr;
149 jmethodID getDataTerminalReady = nullptr;
150 jmethodID setDataTerminalReady = nullptr;
151 jmethodID getRingIndicator = nullptr;
152 jmethodID getRequestToSend = nullptr;
153 jmethodID setRequestToSend = nullptr;
154 jmethodID getControlLines = nullptr;
155 jmethodID getFlowControl = nullptr;
156 jmethodID setFlowControl = nullptr;
157 jmethodID purgeBuffers = nullptr;
158 jmethodID setBreak = nullptr;
159 jmethodID startIoManager = nullptr;
160 jmethodID stopIoManager = nullptr;
161 jmethodID ioManagerRunning = nullptr;
162};
163
165static bool s_methodsCached = false;
166static QMutex s_cacheLock;
167static jclass s_serialManagerClass = nullptr;
168
169static bool cacheMethodIds(JNIEnv* env, jclass javaClass)
170{
171 struct MethodDef
172 {
173 jmethodID* target;
174 const char* name;
175 const char* sig;
176 };
177
178 const MethodDef defs[] = {
179 {&s_methods.availableDevicesInfo, "availableDevicesInfo", "()[Ljava/lang/String;"},
180 {&s_methods.getDeviceId, "getDeviceId", "(Ljava/lang/String;)I"},
181 {&s_methods.getDeviceHandle, "getDeviceHandle", "(I)I"},
182 {&s_methods.open, "open", "(Ljava/lang/String;J)I"},
183 {&s_methods.close, "close", "(I)Z"},
184 {&s_methods.isDeviceNameOpen, "isDeviceNameOpen", "(Ljava/lang/String;)Z"},
185 {&s_methods.read, "read", "(III)[B"},
186 {&s_methods.write, "write", "(I[BII)I"},
187 {&s_methods.writeAsync, "writeAsync", "(I[BI)I"},
188 {&s_methods.setParameters, "setParameters", "(IIIII)Z"},
189 {&s_methods.getCarrierDetect, "getCarrierDetect", "(I)Z"},
190 {&s_methods.getClearToSend, "getClearToSend", "(I)Z"},
191 {&s_methods.getDataSetReady, "getDataSetReady", "(I)Z"},
192 {&s_methods.getDataTerminalReady, "getDataTerminalReady", "(I)Z"},
193 {&s_methods.setDataTerminalReady, "setDataTerminalReady", "(IZ)Z"},
194 {&s_methods.getRingIndicator, "getRingIndicator", "(I)Z"},
195 {&s_methods.getRequestToSend, "getRequestToSend", "(I)Z"},
196 {&s_methods.setRequestToSend, "setRequestToSend", "(IZ)Z"},
197 {&s_methods.getControlLines, "getControlLines", "(I)[I"},
198 {&s_methods.getFlowControl, "getFlowControl", "(I)I"},
199 {&s_methods.setFlowControl, "setFlowControl", "(II)Z"},
200 {&s_methods.purgeBuffers, "purgeBuffers", "(IZZ)Z"},
201 {&s_methods.setBreak, "setBreak", "(IZ)Z"},
202 {&s_methods.startIoManager, "startIoManager", "(I)Z"},
203 {&s_methods.stopIoManager, "stopIoManager", "(I)Z"},
204 {&s_methods.ioManagerRunning, "ioManagerRunning", "(I)Z"},
205 };
206
207 for (const auto& def : defs) {
208 *def.target = env->GetStaticMethodID(javaClass, def.name, def.sig);
209 if (!*def.target) {
210 qCWarning(AndroidSerialLog) << "Failed to cache method:" << def.name << def.sig;
211 (void)QJniEnvironment::checkAndClearExceptions(env);
212 return false;
213 }
214 }
215
216 s_methodsCached = true;
217 qCDebug(AndroidSerialLog) << "All JNI method IDs cached successfully";
218 return true;
219}
220
221// ----------------------------------------------------------------------------
222// Class resolution
223// ----------------------------------------------------------------------------
224
226{
227 QMutexLocker locker(&s_cacheLock);
228
231 }
232
233 QJniEnvironment env;
234 if (!env.isValid()) {
235 qCWarning(AndroidSerialLog) << "Invalid QJniEnvironment";
236 return nullptr;
237 }
238
240 const jclass resolvedClass = env.findClass(kJniUsbSerialManagerClassName);
241 if (!resolvedClass) {
242 qCWarning(AndroidSerialLog) << "Class Not Found:" << kJniUsbSerialManagerClassName;
243 return nullptr;
244 }
245
246 s_serialManagerClass = static_cast<jclass>(env->NewGlobalRef(resolvedClass));
247 if (env->GetObjectRefType(resolvedClass) == JNILocalRefType) {
248 env->DeleteLocalRef(resolvedClass);
249 }
250
252 qCWarning(AndroidSerialLog) << "Failed to create global ref for class:" << kJniUsbSerialManagerClassName;
253 (void)env.checkAndClearExceptions();
254 return nullptr;
255 }
256 }
257
258 if (!s_methodsCached && !cacheMethodIds(env.jniEnv(), s_serialManagerClass)) {
259 qCWarning(AndroidSerialLog) << "Failed to cache JNI method IDs";
260 env->DeleteGlobalRef(s_serialManagerClass);
261 s_serialManagerClass = nullptr;
262 s_methods = {};
263 (void)env.checkAndClearExceptions();
264 return nullptr;
265 }
266
267 s_methodsCached = true;
268 (void)env.checkAndClearExceptions();
270}
271
273{
274 QMutexLocker locker(&s_cacheLock);
275 QJniEnvironment env;
276 if (s_serialManagerClass && env.isValid()) {
277 env->DeleteGlobalRef(s_serialManagerClass);
278 }
279 s_serialManagerClass = nullptr;
280 s_methods = {};
281 s_methodsCached = false;
282}
283
284// ----------------------------------------------------------------------------
285// Native method registration
286// ----------------------------------------------------------------------------
287
288// Forward declarations for JNI callbacks (defined below)
289static void jniDeviceHasDisconnected(JNIEnv* env, jobject obj, jlong token);
290static void jniDeviceNewData(JNIEnv* env, jobject obj, jlong token, jbyteArray data);
291static void jniDeviceException(JNIEnv* env, jobject obj, jlong token, jstring message);
292
294{
295 qCDebug(AndroidSerialLog) << "Registering Native Functions";
296
297 const JNINativeMethod javaMethods[]{
298 {"nativeDeviceHasDisconnected", "(J)V", reinterpret_cast<void*>(jniDeviceHasDisconnected)},
299 {"nativeDeviceNewData", "(J[B)V", reinterpret_cast<void*>(jniDeviceNewData)},
300 {"nativeDeviceException", "(JLjava/lang/String;)V", reinterpret_cast<void*>(jniDeviceException)},
301 };
302
303 QJniEnvironment env;
304 if (!env.registerNativeMethods(kJniUsbSerialManagerClassName, javaMethods, std::size(javaMethods))) {
305 qCWarning(AndroidSerialLog) << "Failed to register native methods for" << kJniUsbSerialManagerClassName;
306 return;
307 }
308
309 if (!getSerialManagerClass()) {
310 qCWarning(AndroidSerialLog) << "Failed to cache JNI method IDs";
311 return;
312 }
313
314 qCDebug(AndroidSerialLog) << "Native Functions Registered Successfully";
315}
316
317// ----------------------------------------------------------------------------
318// JNI callbacks (called from Java threads)
319// ----------------------------------------------------------------------------
320
321static void jniDeviceHasDisconnected(JNIEnv*, jobject, jlong token)
322{
323 if (token == 0) {
324 qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected called with token=0";
325 return;
326 }
327
328 QPointer<QSerialPort> serialPort;
329 {
330 QReadLocker locker(&s_ptrLock);
331 serialPort = lookupPortByTokenLocked(token);
332 if (!serialPort) {
333 qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected: stale token, object already destroyed";
334 return;
335 }
336 qCDebug(AndroidSerialLog) << "Device disconnected:" << serialPort->portName();
337 }
338
340 serialPort.data(),
341 [token]() {
342 QSerialPortPrivate* const p = lookupByToken(token);
343 if (!p) {
344 qCDebug(AndroidSerialLog) << "Token already invalidated in nativeDeviceHasDisconnected";
345 return;
346 }
347
348 QSerialPort* const port = qobject_cast<QSerialPort*>(p->q_ptr);
349 if (port && port->isOpen()) {
350 port->close();
351 qCDebug(AndroidSerialLog) << "Serial port closed in nativeDeviceHasDisconnected";
352 } else {
353 qCDebug(AndroidSerialLog) << "Serial port was already closed in nativeDeviceHasDisconnected";
354 }
355 },
356 "nativeDeviceHasDisconnected")) {
357 qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected: failed to dispatch cleanup";
358 }
359}
360
361static void jniDeviceNewData(JNIEnv* env, jobject, jlong token, jbyteArray data)
362{
363 constexpr jsize kMaxNativePayloadBytes = static_cast<jsize>(MAX_READ_SIZE);
364
365 if (token == 0) {
366 qCWarning(AndroidSerialLog) << "nativeDeviceNewData called with token=0";
367 return;
368 }
369
370 if (!data) {
371 qCWarning(AndroidSerialLog) << "nativeDeviceNewData called with null data";
372 return;
373 }
374
375 const jsize len = env->GetArrayLength(data);
376 if (len <= 0) {
377 qCWarning(AndroidSerialLog) << "nativeDeviceNewData received empty data array";
378 return;
379 }
380
381 const jsize cappedLen = (len > kMaxNativePayloadBytes) ? kMaxNativePayloadBytes : len;
382 if (cappedLen != len) {
383 qCWarning(AndroidSerialLog) << "nativeDeviceNewData payload exceeds limit, truncating from" << len << "to"
384 << cappedLen << "bytes";
385 }
386
387 QByteArray payload(cappedLen, Qt::Uninitialized);
388 env->GetByteArrayRegion(data, 0, cappedLen, reinterpret_cast<jbyte*>(payload.data()));
389 if (QJniEnvironment::checkAndClearExceptions(env)) {
390 qCWarning(AndroidSerialLog) << "nativeDeviceNewData failed to copy JNI byte array";
391 return;
392 }
393
394 {
395 // Deliver inline while holding read lock so unregister/destroy cannot
396 // invalidate the pointer until this handoff is complete.
397 QReadLocker locker(&s_ptrLock);
398 QSerialPortPrivate* const serialPortPrivate = s_tokenToPtr.value(token, nullptr);
399 if (!serialPortPrivate) {
400 qCWarning(AndroidSerialLog) << "nativeDeviceNewData: stale token, object already destroyed";
401 return;
402 }
403
404 serialPortPrivate->newDataArrived(payload.constData(), payload.size());
405 }
406}
407
408static void jniDeviceException(JNIEnv*, jobject, jlong token, jstring message)
409{
410 if (token == 0) {
411 qCWarning(AndroidSerialLog) << "nativeDeviceException called with token=0";
412 return;
413 }
414
415 if (!message) {
416 qCWarning(AndroidSerialLog) << "nativeDeviceException called with null message";
417 return;
418 }
419
420 const QString exceptionMessage = QJniObject(message).toString();
421
422 QPointer<QSerialPort> serialPort;
423 {
424 QReadLocker locker(&s_ptrLock);
425 serialPort = lookupPortByTokenLocked(token);
426 if (!serialPort) {
427 qCWarning(AndroidSerialLog) << "nativeDeviceException: stale token, object already destroyed";
428 return;
429 }
430 }
431
432 qCWarning(AndroidSerialLog) << "Exception from Java:" << exceptionMessage;
433
435 serialPort.data(),
436 [token, exceptionMessage]() {
437 QSerialPortPrivate* const p = lookupByToken(token);
438 if (!p) {
439 qCDebug(AndroidSerialLog) << "Token already invalidated in nativeDeviceException";
440 return;
441 }
442
443 p->exceptionArrived(exceptionMessage);
444 },
445 "nativeDeviceException")) {
446 qCWarning(AndroidSerialLog) << "nativeDeviceException: failed to dispatch exception callback";
447 }
448}
449
450// ----------------------------------------------------------------------------
451// Helper: get env + class + check cached method in one shot
452// ----------------------------------------------------------------------------
453
455{
456 QJniEnvironment env;
457 jclass cls = nullptr;
458 bool valid = false;
459};
460
461static bool getContext(JniContext& ctx, const char* caller)
462{
463 if (!ctx.env.isValid()) {
464 qCWarning(AndroidSerialLog) << "Invalid QJniEnvironment in" << caller;
465 return false;
466 }
467
469 if (!ctx.cls) {
470 qCWarning(AndroidSerialLog) << "getSerialManagerClass returned null in" << caller;
471 return false;
472 }
473
474 ctx.valid = true;
475 return true;
476}
477
478// ----------------------------------------------------------------------------
479// Device enumeration
480// ----------------------------------------------------------------------------
481
482QList<QSerialPortInfo> availableDevices()
483{
484 QList<QSerialPortInfo> serialPortInfoList;
485
486 JniContext ctx;
487 if (!getContext(ctx, "availableDevices"))
488 return serialPortInfoList;
489
491 ctx.env.jniEnv(),
492 static_cast<jobjectArray>(ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.availableDevicesInfo)));
493 if (!objArray.get()) {
494 qCDebug(AndroidSerialLog) << "availableDevicesInfo returned null";
495 (void)ctx.env.checkAndClearExceptions();
496 return serialPortInfoList;
497 }
498
499 if (ctx.env.checkAndClearExceptions()) {
500 qCWarning(AndroidSerialLog) << "Exception occurred while calling availableDevicesInfo";
501 return serialPortInfoList;
502 }
503
504 const jsize count = ctx.env->GetArrayLength(objArray.get());
505 for (jsize i = 0; i < count; ++i) {
507 ctx.env.jniEnv(), static_cast<jstring>(ctx.env->GetObjectArrayElement(objArray.get(), i)));
508 if (!jstr.get()) {
509 qCWarning(AndroidSerialLog) << "Null string at index" << i;
510 continue;
511 }
512
513 const QStringList strList = QJniObject(jstr.get()).toString().split(QLatin1Char('\t'));
514
515 if (strList.size() < 6) {
516 qCWarning(AndroidSerialLog) << "Invalid device info at index" << i << ":" << strList;
517 continue;
518 }
519
520 bool pidOK, vidOK;
523 info.device = strList[0];
524 info.description = strList[1];
525 info.manufacturer = strList[2];
526 info.serialNumber = strList[3];
527 info.productIdentifier = strList[4].toInt(&pidOK);
528 info.hasProductIdentifier = (pidOK && (info.productIdentifier != INVALID_DEVICE_ID));
529 info.vendorIdentifier = strList[5].toInt(&vidOK);
530 info.hasVendorIdentifier = (vidOK && (info.vendorIdentifier != INVALID_DEVICE_ID));
531
532 serialPortInfoList.append(info);
533 }
534
535 (void)ctx.env.checkAndClearExceptions();
536
537 return serialPortInfoList;
538}
539
540// ----------------------------------------------------------------------------
541// Device ID / handle lookup
542// ----------------------------------------------------------------------------
543
544int getDeviceId(const QString& portName)
545{
546 const QJniObject name = QJniObject::fromString(portName);
547 if (!name.isValid()) {
548 qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in getDeviceId";
549 return -1;
550 }
551
552 JniContext ctx;
553 if (!getContext(ctx, "getDeviceId"))
554 return -1;
555
556 jint result = -1;
558 AndroidSerialLog(), result, name.object<jstring>())) {
559 return -1;
560 }
561
562 return static_cast<int>(result);
563}
564
565int getDeviceHandle(int deviceId)
566{
567 JniContext ctx;
568 if (!getContext(ctx, "getDeviceHandle"))
569 return -1;
570
571 jint result = -1;
573 AndroidSerialLog(), result, static_cast<jint>(deviceId))) {
574 return -1;
575 }
576
577 return static_cast<int>(result);
578}
579
580// ----------------------------------------------------------------------------
581// Open / close / isOpen
582// ----------------------------------------------------------------------------
583
584int open(const QString& portName, QSerialPortPrivate* classPtr)
585{
586 if (!classPtr) {
587 qCWarning(AndroidSerialLog) << "open called with null serialPort";
588 return INVALID_DEVICE_ID;
589 }
590
591 const jlong token = lookupToken(classPtr);
592 if (token == 0) {
593 qCWarning(AndroidSerialLog) << "open called with unregistered pointer — call registerPointer first";
594 return INVALID_DEVICE_ID;
595 }
596
597 const QJniObject name = QJniObject::fromString(portName);
598 if (!name.isValid()) {
599 qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in open";
600 return INVALID_DEVICE_ID;
601 }
602
603 JniContext ctx;
604 if (!getContext(ctx, "open"))
605 return INVALID_DEVICE_ID;
606
607 jint deviceId = INVALID_DEVICE_ID;
608 if (!AndroidInterface::callStaticIntMethod(ctx.env, ctx.cls, s_methods.open, "open", AndroidSerialLog(), deviceId,
609 name.object<jstring>(), token)) {
610 return INVALID_DEVICE_ID;
611 }
612
613 return static_cast<int>(deviceId);
614}
615
616bool close(int deviceId)
617{
618 JniContext ctx;
619 if (!getContext(ctx, "close"))
620 return false;
621
622 jboolean result = JNI_FALSE;
623 if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.close, "close", AndroidSerialLog(),
624 result, static_cast<jint>(deviceId))) {
625 return false;
626 }
627
628 return (result == JNI_TRUE);
629}
630
631bool isOpen(const QString& portName)
632{
633 const QJniObject name = QJniObject::fromString(portName);
634 if (!name.isValid()) {
635 qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in isOpen";
636 return false;
637 }
638
639 JniContext ctx;
640 if (!getContext(ctx, "isOpen"))
641 return false;
642
643 jboolean result = JNI_FALSE;
645 AndroidSerialLog(), result, name.object<jstring>())) {
646 return false;
647 }
648
649 return (result == JNI_TRUE);
650}
651
652// ----------------------------------------------------------------------------
653// Read / write
654// ----------------------------------------------------------------------------
655
656QByteArray read(int deviceId, int length, int timeout)
657{
658 JniContext ctx;
659 if (!getContext(ctx, "read"))
660 return QByteArray();
661
663 ctx.env.jniEnv(), static_cast<jbyteArray>(
664 ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.read, static_cast<jint>(deviceId),
665 static_cast<jint>(length), static_cast<jint>(timeout))));
666
667 if (!jarray.get()) {
668 qCWarning(AndroidSerialLog) << "read method returned null";
669 (void)ctx.env.checkAndClearExceptions();
670 return QByteArray();
671 }
672
673 if (ctx.env.checkAndClearExceptions()) {
674 qCWarning(AndroidSerialLog) << "Exception occurred while calling read";
675 return QByteArray();
676 }
677
678 const jsize len = ctx.env->GetArrayLength(jarray.get());
679 jbyte* const bytes = ctx.env->GetByteArrayElements(jarray.get(), nullptr);
680 if (!bytes) {
681 qCWarning(AndroidSerialLog) << "Failed to get byte array elements in read";
682 return QByteArray();
683 }
684
685 const QByteArray data(reinterpret_cast<char*>(bytes), len);
686 ctx.env->ReleaseByteArrayElements(jarray.get(), bytes, JNI_ABORT);
687
688 return data;
689}
690
691int write(int deviceId, const char* data, int length, int timeout, bool async)
692{
693 if (!data || length <= 0) {
694 qCWarning(AndroidSerialLog) << "Invalid data or length in write";
695 return -1;
696 }
697
698 JniContext ctx;
699 if (!getContext(ctx, "write"))
700 return -1;
701
703 ctx.env->NewByteArray(static_cast<jsize>(length)));
704 if (!jarray.get()) {
705 qCWarning(AndroidSerialLog) << "Failed to create jbyteArray in write";
706 return -1;
707 }
708
709 ctx.env->SetByteArrayRegion(jarray.get(), 0, static_cast<jsize>(length), reinterpret_cast<const jbyte*>(data));
710 if (ctx.env.checkAndClearExceptions()) {
711 qCWarning(AndroidSerialLog) << "Exception occurred while setting byte array region in write";
712 return -1;
713 }
714
715 jint result;
716 if (async) {
717 result = ctx.env->CallStaticIntMethod(ctx.cls, s_methods.writeAsync, static_cast<jint>(deviceId), jarray.get(),
718 static_cast<jint>(timeout));
719 } else {
720 result = ctx.env->CallStaticIntMethod(ctx.cls, s_methods.write, static_cast<jint>(deviceId), jarray.get(),
721 static_cast<jint>(length), static_cast<jint>(timeout));
722 }
723
724 if (ctx.env.checkAndClearExceptions()) {
725 qCWarning(AndroidSerialLog) << "Exception occurred while calling write/writeAsync";
726 return -1;
727 }
728
729 return static_cast<int>(result);
730}
731
732// ----------------------------------------------------------------------------
733// Port configuration
734// ----------------------------------------------------------------------------
735
736bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity)
737{
738 JniContext ctx;
739 if (!getContext(ctx, "setParameters"))
740 return false;
741
742 jboolean result = JNI_FALSE;
744 AndroidSerialLog(), result, static_cast<jint>(deviceId),
745 static_cast<jint>(baudRate), static_cast<jint>(dataBits),
746 static_cast<jint>(stopBits), static_cast<jint>(parity))) {
747 return false;
748 }
749
750 return (result == JNI_TRUE);
751}
752
753// ----------------------------------------------------------------------------
754// Control line helpers (DRY macro for bool getters)
755// ----------------------------------------------------------------------------
756
757static bool callBoolMethod(jmethodID method, int deviceId, const char* name)
758{
759 JniContext ctx;
760 if (!getContext(ctx, name))
761 return false;
762
763 jboolean result = JNI_FALSE;
764 if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, method, name, AndroidSerialLog(), result,
765 static_cast<jint>(deviceId))) {
766 return false;
767 }
768
769 return (result == JNI_TRUE);
770}
771
772static bool callBoolSetMethod(jmethodID method, int deviceId, bool set, const char* name)
773{
774 JniContext ctx;
775 if (!getContext(ctx, name))
776 return false;
777
778 const jboolean jSet = set ? JNI_TRUE : JNI_FALSE;
779 jboolean result = JNI_FALSE;
780 if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, method, name, AndroidSerialLog(), result,
781 static_cast<jint>(deviceId), jSet)) {
782 return false;
783 }
784
785 return (result == JNI_TRUE);
786}
787
788// ----------------------------------------------------------------------------
789// Control lines
790// ----------------------------------------------------------------------------
791
792bool getCarrierDetect(int deviceId)
793{
794 return callBoolMethod(s_methods.getCarrierDetect, deviceId, "getCarrierDetect");
795}
796
797bool getClearToSend(int deviceId)
798{
799 return callBoolMethod(s_methods.getClearToSend, deviceId, "getClearToSend");
800}
801
802bool getDataSetReady(int deviceId)
803{
804 return callBoolMethod(s_methods.getDataSetReady, deviceId, "getDataSetReady");
805}
806
807bool getDataTerminalReady(int deviceId)
808{
809 return callBoolMethod(s_methods.getDataTerminalReady, deviceId, "getDataTerminalReady");
810}
811
812bool getRingIndicator(int deviceId)
813{
814 return callBoolMethod(s_methods.getRingIndicator, deviceId, "getRingIndicator");
815}
816
817bool getRequestToSend(int deviceId)
818{
819 return callBoolMethod(s_methods.getRequestToSend, deviceId, "getRequestToSend");
820}
821
822bool setDataTerminalReady(int deviceId, bool set)
823{
824 return callBoolSetMethod(s_methods.setDataTerminalReady, deviceId, set, "setDataTerminalReady");
825}
826
827bool setRequestToSend(int deviceId, bool set)
828{
829 return callBoolSetMethod(s_methods.setRequestToSend, deviceId, set, "setRequestToSend");
830}
831
832QSerialPort::PinoutSignals getControlLines(int deviceId)
833{
834 JniContext ctx;
835 if (!getContext(ctx, "getControlLines"))
836 return QSerialPort::PinoutSignals();
837
839 ctx.env.jniEnv(), static_cast<jintArray>(ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.getControlLines,
840 static_cast<jint>(deviceId))));
841 if (!jarray.get()) {
842 qCWarning(AndroidSerialLog) << "getControlLines returned null";
843 (void)ctx.env.checkAndClearExceptions();
844 return QSerialPort::PinoutSignals();
845 }
846
847 if (ctx.env.checkAndClearExceptions()) {
848 qCWarning(AndroidSerialLog) << "Exception occurred while calling getControlLines";
849 return QSerialPort::PinoutSignals();
850 }
851
852 jint* const ints = ctx.env->GetIntArrayElements(jarray.get(), nullptr);
853 if (!ints) {
854 qCWarning(AndroidSerialLog) << "Failed to get int array elements in getControlLines";
855 return QSerialPort::PinoutSignals();
856 }
857
858 const jsize len = ctx.env->GetArrayLength(jarray.get());
859 QSerialPort::PinoutSignals data = QSerialPort::PinoutSignals();
860
861 for (jsize i = 0; i < len; ++i) {
862 switch (ints[i]) {
863 case RtsControlLine:
865 break;
866 case CtsControlLine:
868 break;
869 case DtrControlLine:
871 break;
872 case DsrControlLine:
874 break;
875 case CdControlLine:
877 break;
878 case RiControlLine:
880 break;
881 default:
882 qCWarning(AndroidSerialLog) << "Unknown ControlLine value:" << ints[i];
883 break;
884 }
885 }
886
887 ctx.env->ReleaseIntArrayElements(jarray.get(), ints, JNI_ABORT);
888 (void)ctx.env.checkAndClearExceptions();
889
890 return data;
891}
892
893// ----------------------------------------------------------------------------
894// Flow control
895// ----------------------------------------------------------------------------
896
897int getFlowControl(int deviceId)
898{
899 JniContext ctx;
900 if (!getContext(ctx, "getFlowControl"))
902
903 jint flowControl = QSerialPort::NoFlowControl;
905 AndroidSerialLog(), flowControl, static_cast<jint>(deviceId))) {
907 }
908
909 return static_cast<int>(flowControl);
910}
911
912bool setFlowControl(int deviceId, int flowControl)
913{
914 JniContext ctx;
915 if (!getContext(ctx, "setFlowControl"))
916 return false;
917
918 jboolean result = JNI_FALSE;
920 AndroidSerialLog(), result, static_cast<jint>(deviceId),
921 static_cast<jint>(flowControl))) {
922 return false;
923 }
924
925 return result == JNI_TRUE;
926}
927
928// ----------------------------------------------------------------------------
929// Buffer / break
930// ----------------------------------------------------------------------------
931
932bool purgeBuffers(int deviceId, bool input, bool output)
933{
934 JniContext ctx;
935 if (!getContext(ctx, "purgeBuffers"))
936 return false;
937
938 const jboolean jInput = input ? JNI_TRUE : JNI_FALSE;
939 const jboolean jOutput = output ? JNI_TRUE : JNI_FALSE;
940
941 jboolean result = JNI_FALSE;
943 AndroidSerialLog(), result, static_cast<jint>(deviceId), jInput,
944 jOutput)) {
945 return false;
946 }
947
948 return (result == JNI_TRUE);
949}
950
951bool setBreak(int deviceId, bool set)
952{
953 return callBoolSetMethod(s_methods.setBreak, deviceId, set, "setBreak");
954}
955
956// ----------------------------------------------------------------------------
957// IO manager (read thread)
958// ----------------------------------------------------------------------------
959
960bool startReadThread(int deviceId)
961{
962 return callBoolMethod(s_methods.startIoManager, deviceId, "startIoManager");
963}
964
965bool stopReadThread(int deviceId)
966{
967 return callBoolMethod(s_methods.stopIoManager, deviceId, "stopIoManager");
968}
969
970bool readThreadRunning(int deviceId)
971{
972 return callBoolMethod(s_methods.ioManagerRunning, deviceId, "ioManagerRunning");
973}
974
975} // namespace AndroidSerial
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static QString portNameFromSystemLocation(const QString &source)
void newDataArrived(const char *bytes, int length)
Provides functions to access serial ports.
Definition qserialport.h:17
@ DataTerminalReadySignal
Definition qserialport.h:97
@ DataCarrierDetectSignal
Definition qserialport.h:98
bool callStaticBooleanMethod(QJniEnvironment &env, jclass cls, jmethodID method, const char *caller, const QLoggingCategory &logCategory, jboolean &result, Args... args)
bool callStaticIntMethod(QJniEnvironment &env, jclass cls, jmethodID method, const char *caller, const QLoggingCategory &logCategory, jint &result, Args... args)
int open(const QString &portName, QSerialPortPrivate *classPtr)
static bool cacheMethodIds(JNIEnv *env, jclass javaClass)
bool getRingIndicator(int deviceId)
void registerPointer(QSerialPortPrivate *ptr)
QByteArray read(int deviceId, int length, int timeout)
static QSerialPortPrivate * lookupByToken(jlong token)
static jclass getSerialManagerClass()
int getDeviceHandle(int deviceId)
static bool s_methodsCached
QList< QSerialPortInfo > availableDevices()
static void jniDeviceNewData(JNIEnv *env, jobject obj, jlong token, jbyteArray data)
static bool callBoolMethod(jmethodID method, int deviceId, const char *name)
static void jniDeviceHasDisconnected(JNIEnv *env, jobject obj, jlong token)
bool getRequestToSend(int deviceId)
bool getDataTerminalReady(int deviceId)
constexpr const char * kJniUsbSerialManagerClassName
static bool getContext(JniContext &ctx, const char *caller)
static QMutex s_cacheLock
static void jniDeviceException(JNIEnv *env, jobject obj, jlong token, jstring message)
static jclass s_serialManagerClass
void unregisterPointer(QSerialPortPrivate *ptr)
static QSerialPort * lookupPortByTokenLocked(jlong token)
static JniMethodCache s_methods
int getDeviceId(const QString &portName)
bool setDataTerminalReady(int deviceId, bool set)
void setNativeMethods()
static bool dispatchToPortObject(QSerialPort *serialPort, Functor &&func, const char *context)
bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity)
bool startReadThread(int deviceId)
int getFlowControl(int deviceId)
QSerialPort::PinoutSignals getControlLines(int deviceId)
bool getDataSetReady(int deviceId)
static QHash< jlong, QSerialPortPrivate * > s_tokenToPtr
bool setRequestToSend(int deviceId, bool set)
bool getClearToSend(int deviceId)
bool purgeBuffers(int deviceId, bool input, bool output)
static QReadWriteLock s_ptrLock
bool getCarrierDetect(int deviceId)
bool isOpen(const QString &portName)
bool readThreadRunning(int deviceId)
bool close(int deviceId)
bool stopReadThread(int deviceId)
static QHash< QSerialPortPrivate *, jlong > s_ptrToToken
static jlong lookupToken(QSerialPortPrivate *ptr)
static bool callBoolSetMethod(jmethodID method, int deviceId, bool set, const char *name)
bool setFlowControl(int deviceId, int flowControl)
bool setBreak(int deviceId, bool set)
constexpr qint64 MAX_READ_SIZE
constexpr int INVALID_DEVICE_ID