diff --git a/.github/mcp-config.json b/.github/mcp-config.json index e69de29bb2d1..be86b6a2d3d6 100644 --- a/.github/mcp-config.json +++ b/.github/mcp-config.json @@ -0,0 +1,7 @@ +{ + "mcpServers": { + "qt-docs": { + "url": "https://qt-docs-mcp.qt.io/mcp" + } + } +} diff --git a/AGENTS.md b/AGENTS.md index bde6cbc6d7c3..fb9ee1010d11 100644 --- a/AGENTS.md +++ b/AGENTS.md @@ -47,6 +47,48 @@ cd .github/scripts && PYTHONPATH=. python3 -m pytest tests/ -q cd tools && uv run --extra scripts --extra test pytest tests/ -q ``` +## Android: Install + Logcat + +Workflow for installing a debug-built APK to a connected device and capturing logs. + +Prereqs (on PATH): `adb`, `zipalign`, `apksigner` (Android `build-tools//`). Debug keystore at `~/.android/debug.keystore` (alias `androiddebugkey`, password `android`). + +```bash +# Adjust APK path to your Qt-Android build kit/configuration +APK=build/Qt_6_10_3_for_Android_arm64_v8a-Debug/android-build-QGroundControl/QGroundControl.apk + +# Re-sign with the debug keystore (Qt's androiddeployqt output is unsigned/misaligned for adb install) +zipalign -p -f 4 "$APK" "${APK%.apk}-aligned.apk" +apksigner sign --ks ~/.android/debug.keystore --ks-pass pass:android --ks-key-alias androiddebugkey \ + --key-pass pass:android --out "${APK%.apk}-signed.apk" "${APK%.apk}-aligned.apk" + +# Install (replace existing); -r keeps data, add -d to allow downgrade +adb install -r "${APK%.apk}-signed.apk" + +# Launch (force-stop first for a clean session) +adb shell am force-stop org.mavlink.qgroundcontrol +adb shell am start -n org.mavlink.qgroundcontrol/.QGCActivity + +# Logcat: clear, then stream QGC + serial-related tags only +adb logcat -c +adb logcat -v time \ + QGroundControl:V QGCActivity:V QGCUsbSerialManager:V QGCUsbPermissionHandler:V \ + QGCFtdiSerialDriver:V QGCSerialListener:V QGCUsbSerialProber:V \ + AsyncUsbWritePump:V UsbSerialEnumerator:V UsbSerialIoBridge:V UsbSerialLifecycle:V '*:S' + +# Enable per-tag VERBOSE for code paths gated on Log.isLoggable(TAG, VERBOSE). +# Tag must be ≤23 chars; setprop survives until reboot. +adb shell setprop log.tag.QGCSerialListener VERBOSE +adb shell setprop log.tag.UsbSerialIoBridge VERBOSE +adb shell setprop log.tag.AsyncUsbWritePump VERBOSE + +# Qt-side verbose categories — set via QT_LOGGING_RULES before launch, or in-app via the log viewer +adb shell am start -n org.mavlink.qgroundcontrol/.QGCActivity \ + --es "QT_LOGGING_RULES" "Android.Serial.Engine.debug=true;VehicleSetup.FirmwareUpgrade.debug=true" +``` + +Tip: run logcat in a background shell (`run_in_background=true`) and grep the captured file rather than streaming into the agent context. + ## Golden Rules 1. **Fact System**: ALL vehicle parameters use Facts. Never create custom parameter storage. diff --git a/android/build.gradle b/android/build.gradle index 414163f1932f..cb4d903ce624 100644 --- a/android/build.gradle +++ b/android/build.gradle @@ -184,6 +184,14 @@ android { lintConfig = file("lint.xml") } + // Local unit tests run on the host JVM against a stub android.jar where every + // framework method throws "not mocked" by default. Return defaults so plain + // android.util.Log calls become no-ops in tests; tests that need real behavior + // mock those methods explicitly (or use Robolectric). + testOptions { + unitTests.returnDefaultValues = true + } + // Do not compress Qt binary resources file aaptOptions { noCompress 'rcc' diff --git a/android/proguard-rules.pro b/android/proguard-rules.pro index 17d99d40d709..e7417370ccce 100644 --- a/android/proguard-rules.pro +++ b/android/proguard-rules.pro @@ -8,23 +8,23 @@ -keepclasseswithmembers class org.mavlink.qgroundcontrol.QGCActivity { native ; } --keepclasseswithmembers class org.mavlink.qgroundcontrol.QGCUsbSerialManager { +-keepclasseswithmembers class org.mavlink.qgroundcontrol.serial.QGCUsbSerialManager { + native ; +} +-keepclasseswithmembers class org.mavlink.qgroundcontrol.QGCNativeLogSink { native ; } # Static methods are resolved from C++ by method name/signature. -keepclassmembers class org.mavlink.qgroundcontrol.QGCActivity { public static *; } --keepclassmembers class org.mavlink.qgroundcontrol.QGCUsbSerialManager { +-keepclassmembers class org.mavlink.qgroundcontrol.serial.QGCUsbSerialManager { public static *; } --keep class org.mavlink.qgroundcontrol.QGCUsbId { *; } --keep class org.mavlink.qgroundcontrol.QGCUsbSerialProber { *; } -keep class org.mavlink.qgroundcontrol.QGCLogger { *; } --keep class org.mavlink.qgroundcontrol.QGCFtdiSerialDriver { *; } --keep class org.mavlink.qgroundcontrol.QGCFtdiSerialDriver$QGCFtdiSerialPort { *; } --keep class org.mavlink.qgroundcontrol.QGCFtdiDriver { *; } +-keep class org.mavlink.qgroundcontrol.QGCNativeLogSink { *; } -keep class org.mavlink.qgroundcontrol.QGCSDLManager { *; } +-keep class org.mavlink.qgroundcontrol.serial.** { *; } # SDL - native method stubs required for JNI registration -keep class org.libsdl.app.** { *; } diff --git a/android/res/xml/device_filter.xml b/android/res/xml/device_filter.xml index 406531c90019..ae430fde677e 100644 --- a/android/res/xml/device_filter.xml +++ b/android/res/xml/device_filter.xml @@ -1,41 +1,125 @@ + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java index 2ff0fa63fbe7..a83e823117ec 100644 --- a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java +++ b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java @@ -20,6 +20,8 @@ import org.freedesktop.gstreamer.GStreamer; +import org.mavlink.qgroundcontrol.serial.QGCUsbSerialManager; + public class QGCActivity extends QtActivity { private static final String TAG = QGCActivity.class.getSimpleName(); private static final String MULTICAST_LOCK_TAG = "QGroundControl"; @@ -39,7 +41,7 @@ public void onCreate(Bundle savedInstanceState) { nativeInit(); setupMulticastLock(); - QGCUsbSerialManager.initialize(this); + QGCUsbSerialManager.createInstance(this); QGCSDLManager.initialize(this); m_storagePermissionController = new QGCStoragePermissionController(this); } @@ -61,7 +63,7 @@ protected void onDestroy() { try { QGCSDLManager.cleanup(); releaseMulticastLock(); - QGCUsbSerialManager.cleanup(this); + QGCUsbSerialManager.destroyInstance(); } catch (final Exception e) { QGCLogger.e(TAG, "Exception onDestroy()", e); } @@ -137,7 +139,7 @@ private String copyFileToDestination(final Uri uri, final String destDir) { if (cursor != null && cursor.moveToFirst()) { final int nameIndex = cursor.getColumnIndex(OpenableColumns.DISPLAY_NAME); if (nameIndex >= 0) { - displayName = cursor.getString(nameIndex); + displayName = cursor.getString(nameIndex); displayName = sanitizeFilename(displayName); } } @@ -314,8 +316,6 @@ public boolean dispatchKeyEvent(KeyEvent event) { // Native C++ functions public native boolean nativeInit(); - public native void qgcLogDebug(final String message); - public native void qgcLogWarning(final String message); public native void nativeStoragePermissionsResult(boolean granted); public native void onImportResult(final String filePath); } diff --git a/android/src/org/mavlink/qgroundcontrol/QGCFtdiDriver.java b/android/src/org/mavlink/qgroundcontrol/QGCFtdiDriver.java deleted file mode 100644 index 5b67b38169a9..000000000000 --- a/android/src/org/mavlink/qgroundcontrol/QGCFtdiDriver.java +++ /dev/null @@ -1,305 +0,0 @@ -package org.mavlink.qgroundcontrol; - -import android.content.Context; -import android.hardware.usb.UsbDevice; -import com.ftdi.j2xx.D2xxManager; -import com.ftdi.j2xx.FT_Device; -import com.hoho.android.usbserial.driver.UsbSerialPort; - -import java.util.ArrayList; -import java.util.Arrays; -import java.util.List; - -final class QGCFtdiDriver { - private static final String TAG = QGCFtdiDriver.class.getSimpleName(); - - private static Context sAppContext; - private static D2xxManager sManager; - - private final FT_Device _device; - - private int _flowControl = UsbSerialPort.FlowControl.NONE.ordinal(); - private boolean _dtr; - private boolean _rts; - - private QGCFtdiDriver(final FT_Device device) { - _device = device; - } - - static void initialize(final Context context) { - sAppContext = context.getApplicationContext(); - try { - sManager = D2xxManager.getInstance(sAppContext); - } catch (D2xxManager.D2xxException e) { - sManager = null; - QGCLogger.w(TAG, "D2XX manager unavailable: " + e.getMessage()); - } catch (Throwable t) { - sManager = null; - QGCLogger.w(TAG, "D2XX manager unavailable: " + t.getMessage()); - } - } - - static void cleanup() { - sManager = null; - sAppContext = null; - } - - static boolean isAvailable() { - return (sManager != null) && (sAppContext != null); - } - - static boolean isFtdiDevice(final UsbDevice device) { - return device != null - && device.getVendorId() == QGCUsbId.VENDOR_FTDI - && QGCUsbId.isSupportedFtdiProductId(device.getProductId()); - } - - static QGCFtdiDriver open(final UsbDevice device) { - if (sManager == null || sAppContext == null || !isFtdiDevice(device)) { - return null; - } - - try { - final FT_Device d2xxDevice = sManager.openByUsbDevice(sAppContext, device); - if (d2xxDevice == null || !d2xxDevice.isOpen()) { - return null; - } - return new QGCFtdiDriver(d2xxDevice); - } catch (Throwable t) { - QGCLogger.w(TAG, "Failed to open D2XX FTDI device " + device.getDeviceName() + ": " + t.getMessage()); - return null; - } - } - - boolean isOpen() { - return _device != null && _device.isOpen(); - } - - void close() { - try { - if (_device != null) { - _device.close(); - } - } catch (Throwable t) { - QGCLogger.w(TAG, "Error closing D2XX device: " + t.getMessage()); - } - } - - int write(final byte[] data, final int length, final int timeoutMSec) { - if (!isOpen() || data == null || length <= 0) { - return -1; - } - - final int writeLength = Math.min(length, data.length); - final byte[] writeData = (writeLength == data.length) ? data : Arrays.copyOf(data, writeLength); - try { - return _device.write(writeData, writeLength, true, timeoutMSec); - } catch (Throwable t) { - QGCLogger.e(TAG, "Error writing D2XX data", t); - return -1; - } - } - - byte[] read(final int length, final int timeoutMs) { - if (!isOpen() || length <= 0) { - return new byte[]{}; - } - - final byte[] buffer = new byte[length]; - try { - final int bytesRead = _device.read(buffer, length, timeoutMs); - if (bytesRead <= 0) { - return new byte[]{}; - } - return (bytesRead < length) ? Arrays.copyOf(buffer, bytesRead) : buffer; - } catch (Throwable t) { - QGCLogger.e(TAG, "Error reading D2XX data", t); - return new byte[]{}; - } - } - - boolean setParameters(final int baudRate, final int dataBits, final int stopBits, final int parity) { - if (!isOpen()) { - return false; - } - try { - final boolean baudOk = _device.setBaudRate(baudRate); - final boolean charsOk = _device.setDataCharacteristics(toD2xxDataBits(dataBits), toD2xxStopBits(stopBits), toD2xxParity(parity)); - return baudOk && charsOk; - } catch (Throwable t) { - QGCLogger.e(TAG, "Error setting D2XX parameters", t); - return false; - } - } - - boolean getControlLine(final UsbSerialPort.ControlLine controlLine) { - if (!isOpen()) { - return false; - } - - try { - final short modemStatus = _device.getModemStatus(); - switch (controlLine) { - case CD: - return (modemStatus & D2xxManager.FT_DCD) != 0; - case CTS: - return (modemStatus & D2xxManager.FT_CTS) != 0; - case DSR: - return (modemStatus & D2xxManager.FT_DSR) != 0; - case DTR: - return _dtr; - case RI: - return (modemStatus & D2xxManager.FT_RI) != 0; - case RTS: - return _rts; - default: - return false; - } - } catch (Throwable t) { - QGCLogger.e(TAG, "Error reading D2XX control line " + controlLine, t); - return false; - } - } - - boolean setControlLine(final UsbSerialPort.ControlLine controlLine, final boolean on) { - if (!isOpen()) { - return false; - } - - try { - switch (controlLine) { - case DTR: - _dtr = on; - return on ? _device.setDtr() : _device.clrDtr(); - case RTS: - _rts = on; - return on ? _device.setRts() : _device.clrRts(); - default: - return false; - } - } catch (Throwable t) { - QGCLogger.e(TAG, "Error setting D2XX control line " + controlLine, t); - return false; - } - } - - int[] getControlLines() { - final List lines = new ArrayList<>(); - if (getControlLine(UsbSerialPort.ControlLine.RTS)) { - lines.add(UsbSerialPort.ControlLine.RTS.ordinal()); - } - if (getControlLine(UsbSerialPort.ControlLine.CTS)) { - lines.add(UsbSerialPort.ControlLine.CTS.ordinal()); - } - if (getControlLine(UsbSerialPort.ControlLine.DTR)) { - lines.add(UsbSerialPort.ControlLine.DTR.ordinal()); - } - if (getControlLine(UsbSerialPort.ControlLine.DSR)) { - lines.add(UsbSerialPort.ControlLine.DSR.ordinal()); - } - if (getControlLine(UsbSerialPort.ControlLine.CD)) { - lines.add(UsbSerialPort.ControlLine.CD.ordinal()); - } - if (getControlLine(UsbSerialPort.ControlLine.RI)) { - lines.add(UsbSerialPort.ControlLine.RI.ordinal()); - } - return lines.stream().mapToInt(Integer::intValue).toArray(); - } - - int getFlowControl() { - return _flowControl; - } - - boolean setFlowControl(final int flowControl) { - if (!isOpen()) { - return false; - } - try { - final short flowMode = toD2xxFlowControl(flowControl); - final boolean result = _device.setFlowControl(flowMode, (byte) 0x11, (byte) 0x13); - if (result) { - _flowControl = flowControl; - } - return result; - } catch (Throwable t) { - QGCLogger.e(TAG, "Error setting D2XX flow control", t); - return false; - } - } - - boolean setBreak(final boolean on) { - if (!isOpen()) { - return false; - } - try { - return on ? _device.setBreakOn() : _device.setBreakOff(); - } catch (Throwable t) { - QGCLogger.e(TAG, "Error setting D2XX break condition", t); - return false; - } - } - - boolean purgeBuffers(final boolean input, final boolean output) { - if (!isOpen()) { - return false; - } - - byte purgeFlags = 0; - if (input) { - purgeFlags |= D2xxManager.FT_PURGE_RX; - } - if (output) { - purgeFlags |= D2xxManager.FT_PURGE_TX; - } - if (purgeFlags == 0) { - return true; - } - - try { - return _device.purge(purgeFlags); - } catch (Throwable t) { - QGCLogger.e(TAG, "Error purging D2XX buffers", t); - return false; - } - } - - private static byte toD2xxDataBits(final int dataBits) { - return (dataBits == 7) ? D2xxManager.FT_DATA_BITS_7 : D2xxManager.FT_DATA_BITS_8; - } - - private static byte toD2xxStopBits(final int stopBits) { - if (stopBits == UsbSerialPort.STOPBITS_2) { - return D2xxManager.FT_STOP_BITS_2; - } - return D2xxManager.FT_STOP_BITS_1; - } - - private static byte toD2xxParity(final int parity) { - switch (parity) { - case UsbSerialPort.PARITY_ODD: - return D2xxManager.FT_PARITY_ODD; - case UsbSerialPort.PARITY_EVEN: - return D2xxManager.FT_PARITY_EVEN; - case UsbSerialPort.PARITY_MARK: - return D2xxManager.FT_PARITY_MARK; - case UsbSerialPort.PARITY_SPACE: - return D2xxManager.FT_PARITY_SPACE; - case UsbSerialPort.PARITY_NONE: - default: - return D2xxManager.FT_PARITY_NONE; - } - } - - private static short toD2xxFlowControl(final int flowControl) { - if (flowControl == UsbSerialPort.FlowControl.RTS_CTS.ordinal()) { - return D2xxManager.FT_FLOW_RTS_CTS; - } - if (flowControl == UsbSerialPort.FlowControl.DTR_DSR.ordinal()) { - return D2xxManager.FT_FLOW_DTR_DSR; - } - if (flowControl == UsbSerialPort.FlowControl.XON_XOFF.ordinal()) { - return D2xxManager.FT_FLOW_XON_XOFF; - } - return D2xxManager.FT_FLOW_NONE; - } -} diff --git a/android/src/org/mavlink/qgroundcontrol/QGCFtdiSerialDriver.java b/android/src/org/mavlink/qgroundcontrol/QGCFtdiSerialDriver.java deleted file mode 100644 index b04ab98eee3e..000000000000 --- a/android/src/org/mavlink/qgroundcontrol/QGCFtdiSerialDriver.java +++ /dev/null @@ -1,432 +0,0 @@ -package org.mavlink.qgroundcontrol; - -import android.hardware.usb.UsbConstants; -import android.hardware.usb.UsbDevice; -import android.hardware.usb.UsbDeviceConnection; -import android.hardware.usb.UsbEndpoint; -import android.hardware.usb.UsbInterface; -import com.hoho.android.usbserial.driver.UsbSerialDriver; -import com.hoho.android.usbserial.driver.UsbSerialPort; - -import java.io.IOException; -import java.util.ArrayList; -import java.util.Collections; -import java.util.EnumSet; -import java.util.List; -import java.util.Map; - -public final class QGCFtdiSerialDriver implements UsbSerialDriver { - private final UsbDevice _device; - private final List _ports; - - public QGCFtdiSerialDriver(final UsbDevice device) { - _device = device; - - final int interfaceCount = device.getInterfaceCount(); - if (interfaceCount <= 0) { - _ports = Collections.emptyList(); - return; - } - final List ports = new ArrayList<>(interfaceCount); - for (int i = 0; i < interfaceCount; i++) { - ports.add(new QGCFtdiSerialPort(this, device, i)); - } - - _ports = Collections.unmodifiableList(ports); - } - - public static Map getSupportedDevices() { - return Collections.singletonMap(QGCUsbId.VENDOR_FTDI, new int[] { - QGCUsbId.DEVICE_FTDI_FT232R, - QGCUsbId.DEVICE_FTDI_FT2232H, - QGCUsbId.DEVICE_FTDI_FT4232H, - QGCUsbId.DEVICE_FTDI_FT232H, - QGCUsbId.DEVICE_FTDI_FT231X - }); - } - - @Override - public UsbDevice getDevice() { - return _device; - } - - @Override - public List getPorts() { - return _ports; - } - - private static final class QGCFtdiSerialPort implements UsbSerialPort { - private final QGCFtdiSerialDriver _driver; - private final UsbDevice _device; - private final int _portNumber; - - private UsbDeviceConnection _connection; - private UsbEndpoint _readEndpoint; - private UsbEndpoint _writeEndpoint; - private QGCFtdiDriver _ftdi; - private int _readQueueBufferCount; - private int _readQueueBufferSize; - - QGCFtdiSerialPort(final QGCFtdiSerialDriver driver, final UsbDevice device, final int portNumber) { - _driver = driver; - _device = device; - _portNumber = portNumber; - } - - @Override - public UsbSerialDriver getDriver() { - return _driver; - } - - @Override - public UsbDevice getDevice() { - return _device; - } - - @Override - public int getPortNumber() { - return _portNumber; - } - - @Override - public UsbEndpoint getWriteEndpoint() { - return _writeEndpoint; - } - - @Override - public UsbEndpoint getReadEndpoint() { - return _readEndpoint; - } - - @Override - public String getSerial() { - try { - return _device.getSerialNumber(); - } catch (SecurityException e) { - return null; - } - } - - @Override - public void setReadQueue(final int bufferCount, final int bufferSize) { - if (bufferCount < 0) { - throw new IllegalArgumentException("Invalid bufferCount"); - } - if (bufferSize < 0) { - throw new IllegalArgumentException("Invalid bufferSize"); - } - - int effectiveBufferSize = bufferSize; - if (isOpen() && (effectiveBufferSize == 0) && (_readEndpoint != null)) { - effectiveBufferSize = _readEndpoint.getMaxPacketSize(); - } - - if (isOpen()) { - if (bufferCount < _readQueueBufferCount) { - throw new IllegalStateException("Cannot reduce bufferCount when port is open"); - } - if ((_readQueueBufferCount != 0) && (_readQueueBufferSize != 0) && (effectiveBufferSize != _readQueueBufferSize)) { - throw new IllegalStateException("Cannot change bufferSize when port is open"); - } - } - - _readQueueBufferCount = bufferCount; - _readQueueBufferSize = effectiveBufferSize; - } - - @Override - public int getReadQueueBufferCount() { - return _readQueueBufferCount; - } - - @Override - public int getReadQueueBufferSize() { - return _readQueueBufferSize; - } - - @Override - public void open(final UsbDeviceConnection connection) throws IOException { - if (isOpen()) { - throw new IOException("Already open"); - } - if (connection == null) { - throw new IOException("Null USB device connection"); - } - - final QGCFtdiDriver ftdi = QGCFtdiDriver.open(_device); - if (ftdi == null || !ftdi.isOpen()) { - throw new IOException("Failed to open D2XX FTDI device " + _device.getDeviceName()); - } - - _connection = connection; - _ftdi = ftdi; - - if (!resolveBulkEndpoints()) { - close(); - throw new IOException("Failed to resolve FTDI bulk endpoints for " + _device.getDeviceName()); - } - } - - @Override - public void close() throws IOException { - if (_ftdi != null) { - _ftdi.close(); - _ftdi = null; - } - - if (_connection != null) { - _connection.close(); - _connection = null; - } - - _readEndpoint = null; - _writeEndpoint = null; - } - - @Override - public int read(final byte[] dest, final int timeout) throws IOException { - return read(dest, dest.length, timeout); - } - - @Override - public int read(final byte[] dest, final int length, final int timeout) throws IOException { - ensureOpen(); - if (dest == null) { - throw new IOException("Null read buffer"); - } - if (length <= 0) { - return 0; - } - - final int readLength = Math.min(length, dest.length); - final byte[] data = _ftdi.read(readLength, timeout); - if (data.length > 0) { - System.arraycopy(data, 0, dest, 0, data.length); - } - return data.length; - } - - @Override - public void write(final byte[] src, final int timeout) throws IOException { - write(src, src.length, timeout); - } - - @Override - public void write(final byte[] src, final int length, final int timeout) throws IOException { - ensureOpen(); - if (src == null) { - throw new IOException("Null write buffer"); - } - if (length <= 0) { - return; - } - - final int writeLength = Math.min(length, src.length); - final int written = _ftdi.write(src, writeLength, timeout); - if (written < writeLength) { - throw new IOException("D2XX write failed or short write: " + written + " / " + writeLength); - } - } - - @Override - public void setParameters(final int baudRate, final int dataBits, final int stopBits, final int parity) throws IOException { - ensureOpen(); - if (!_ftdi.setParameters(baudRate, dataBits, stopBits, parity)) { - throw new IOException("Failed to set FTDI serial parameters"); - } - } - - @Override - public boolean getCD() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.CD); - } - - @Override - public boolean getCTS() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.CTS); - } - - @Override - public boolean getDSR() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.DSR); - } - - @Override - public boolean getDTR() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.DTR); - } - - @Override - public void setDTR(final boolean value) throws IOException { - ensureOpen(); - if (!_ftdi.setControlLine(ControlLine.DTR, value)) { - throw new IOException("Failed to set DTR"); - } - } - - @Override - public boolean getRI() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.RI); - } - - @Override - public boolean getRTS() throws IOException { - ensureOpen(); - return _ftdi.getControlLine(ControlLine.RTS); - } - - @Override - public void setRTS(final boolean value) throws IOException { - ensureOpen(); - if (!_ftdi.setControlLine(ControlLine.RTS, value)) { - throw new IOException("Failed to set RTS"); - } - } - - @Override - public EnumSet getControlLines() throws IOException { - ensureOpen(); - final EnumSet lines = EnumSet.noneOf(ControlLine.class); - if (getRTS()) { - lines.add(ControlLine.RTS); - } - if (getCTS()) { - lines.add(ControlLine.CTS); - } - if (getDTR()) { - lines.add(ControlLine.DTR); - } - if (getDSR()) { - lines.add(ControlLine.DSR); - } - if (getCD()) { - lines.add(ControlLine.CD); - } - if (getRI()) { - lines.add(ControlLine.RI); - } - return lines; - } - - @Override - public EnumSet getSupportedControlLines() { - return EnumSet.of(ControlLine.RTS, ControlLine.CTS, ControlLine.DTR, ControlLine.DSR, ControlLine.CD, ControlLine.RI); - } - - @Override - public void setFlowControl(final FlowControl flowControl) throws IOException { - ensureOpen(); - if (flowControl == FlowControl.XON_XOFF_INLINE) { - throw new IOException("XON/XOFF inline flow control is not supported by D2XX adapter"); - } - - if (!_ftdi.setFlowControl(flowControl.ordinal())) { - throw new IOException("Failed to set flow control: " + flowControl); - } - } - - @Override - public FlowControl getFlowControl() { - if (!isOpen()) { - return FlowControl.NONE; - } - final int ordinal = _ftdi.getFlowControl(); - final FlowControl[] values = FlowControl.values(); - if (ordinal < 0 || ordinal >= values.length) { - return FlowControl.NONE; - } - return values[ordinal]; - } - - @Override - public EnumSet getSupportedFlowControl() { - return EnumSet.of(FlowControl.NONE, FlowControl.RTS_CTS, FlowControl.DTR_DSR, FlowControl.XON_XOFF); - } - - @Override - public boolean getXON() throws IOException { - ensureOpen(); - return false; - } - - @Override - public void purgeHwBuffers(final boolean purgeReadBuffers, final boolean purgeWriteBuffers) throws IOException { - ensureOpen(); - if (!_ftdi.purgeBuffers(purgeReadBuffers, purgeWriteBuffers)) { - throw new IOException("Failed to purge FTDI buffers"); - } - } - - @Override - public void setBreak(final boolean value) throws IOException { - ensureOpen(); - if (!_ftdi.setBreak(value)) { - throw new IOException("Failed to set break condition"); - } - } - - @Override - public boolean isOpen() { - return _ftdi != null && _ftdi.isOpen(); - } - - private void ensureOpen() throws IOException { - if (!isOpen()) { - throw new IOException("Port not open"); - } - } - - private boolean resolveBulkEndpoints() { - UsbEndpoint read = null; - UsbEndpoint write = null; - - if (_portNumber < _device.getInterfaceCount()) { - final UsbInterface usbInterface = _device.getInterface(_portNumber); - for (int e = 0; e < usbInterface.getEndpointCount(); e++) { - final UsbEndpoint endpoint = usbInterface.getEndpoint(e); - if (endpoint.getType() != UsbConstants.USB_ENDPOINT_XFER_BULK) { - continue; - } - if (endpoint.getDirection() == UsbConstants.USB_DIR_IN && read == null) { - read = endpoint; - } else if (endpoint.getDirection() == UsbConstants.USB_DIR_OUT && write == null) { - write = endpoint; - } - } - } - - // Fallback to global endpoint scan for devices that don't expose - // interface-per-port semantics. - if (read == null || write == null) { - for (int i = 0; i < _device.getInterfaceCount(); i++) { - final UsbInterface usbInterface = _device.getInterface(i); - for (int e = 0; e < usbInterface.getEndpointCount(); e++) { - final UsbEndpoint endpoint = usbInterface.getEndpoint(e); - if (endpoint.getType() != UsbConstants.USB_ENDPOINT_XFER_BULK) { - continue; - } - if (endpoint.getDirection() == UsbConstants.USB_DIR_IN && read == null) { - read = endpoint; - } else if (endpoint.getDirection() == UsbConstants.USB_DIR_OUT && write == null) { - write = endpoint; - } - } - - if (read != null && write != null) { - break; - } - } - } - - _readEndpoint = read; - _writeEndpoint = write; - - return _readEndpoint != null && _writeEndpoint != null; - } - } -} diff --git a/android/src/org/mavlink/qgroundcontrol/QGCLogger.java b/android/src/org/mavlink/qgroundcontrol/QGCLogger.java index b117a6fac6cc..24a9a6232e8a 100644 --- a/android/src/org/mavlink/qgroundcontrol/QGCLogger.java +++ b/android/src/org/mavlink/qgroundcontrol/QGCLogger.java @@ -2,14 +2,37 @@ import android.util.Log; +import java.util.function.Supplier; + /** * A centralized logging utility that manages log messages across the application. * It controls log levels and formats based on build configurations. + * + *

Each log call is mirrored to {@link QGCNativeLogSink} so that Java log + * output appears in the Qt logging system (and therefore in QGC's log viewer). + * If the native library is not yet loaded, the mirror call is silently skipped + * (see {@link QGCNativeLogSink#log}). + * + *

Overloads taking {@link Supplier Supplier<String>} defer message + * construction until after the level gate. Prefer them on hot paths where + * the message would otherwise build via string concatenation on every call: + *

+ *     QGCLogger.d(TAG, () -> "Large payload (" + data.length + " bytes)");
+ * 
+ * The lambda is only invoked when the level is enabled, eliminating the + * per-call allocation on release builds (debug level) and on any call that + * the short-circuit gate would have dropped. */ public class QGCLogger { // Determine if the build is a debug build private static final boolean DEBUG = BuildConfig.DEBUG; + /** True if debug-level logging is enabled. Callers on hot paths can + * guard expensive diagnostics themselves: {@code if (QGCLogger.isDebugEnabled()) ...}. */ + public static boolean isDebugEnabled() { + return DEBUG; + } + /** * Logs a debug message. * @@ -19,6 +42,32 @@ public class QGCLogger { public static void d(String tag, String message) { if (DEBUG) { Log.d(tag, message); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_DEBUG, tag, message); + } + } + + /** Debug log that defers message construction via a {@link Supplier}. */ + public static void d(String tag, Supplier message) { + if (DEBUG) { + final String msg = message.get(); + Log.d(tag, msg); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_DEBUG, tag, msg); + } + } + + /** Verbose log gated by per-tag {@code adb shell setprop log.tag. VERBOSE} (≤23 chars). */ + public static void v(String tag, String message) { + if (Log.isLoggable(tag, Log.VERBOSE)) { + Log.v(tag, message); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_DEBUG, tag, message); + } + } + + public static void v(String tag, Supplier message) { + if (Log.isLoggable(tag, Log.VERBOSE)) { + final String msg = message.get(); + Log.v(tag, msg); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_DEBUG, tag, msg); } } @@ -30,6 +79,14 @@ public static void d(String tag, String message) { */ public static void i(String tag, String message) { Log.i(tag, message); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_INFO, tag, message); + } + + /** Info log that defers message construction via a {@link Supplier}. */ + public static void i(String tag, Supplier message) { + final String msg = message.get(); + Log.i(tag, msg); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_INFO, tag, msg); } /** @@ -40,6 +97,14 @@ public static void i(String tag, String message) { */ public static void w(String tag, String message) { Log.w(tag, message); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_WARNING, tag, message); + } + + /** Warning log that defers message construction via a {@link Supplier}. */ + public static void w(String tag, Supplier message) { + final String msg = message.get(); + Log.w(tag, msg); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_WARNING, tag, msg); } /** @@ -51,6 +116,8 @@ public static void w(String tag, String message) { */ public static void w(String tag, String message, Throwable throwable) { Log.w(tag, message, throwable); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_WARNING, tag, + message + ": " + throwable.getMessage()); } /** @@ -62,6 +129,8 @@ public static void w(String tag, String message, Throwable throwable) { */ public static void e(String tag, String message, Throwable throwable) { Log.e(tag, message, throwable); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_ERROR, tag, + message + ": " + throwable.getMessage()); } /** @@ -72,5 +141,13 @@ public static void e(String tag, String message, Throwable throwable) { */ public static void e(String tag, String message) { Log.e(tag, message); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_ERROR, tag, message); + } + + /** Error log that defers message construction via a {@link Supplier}. */ + public static void e(String tag, Supplier message) { + final String msg = message.get(); + Log.e(tag, msg); + QGCNativeLogSink.log(QGCNativeLogSink.LEVEL_ERROR, tag, msg); } } diff --git a/android/src/org/mavlink/qgroundcontrol/QGCNativeLogSink.java b/android/src/org/mavlink/qgroundcontrol/QGCNativeLogSink.java new file mode 100644 index 000000000000..f7a270ce6cfd --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/QGCNativeLogSink.java @@ -0,0 +1,55 @@ +package org.mavlink.qgroundcontrol; + +/** + * Bridges Java log output into the QGC native (Qt) logging system. + * + *

Each log call is forwarded via JNI to {@code nativeLog}, which maps the + * level ordinal to the appropriate {@code qCDebug/qCInfo/qCWarning/qCCritical} + * category on the C++ side. + * + *

JNI availability is tested lazily on the first call. If the native + * library is not yet loaded (e.g. during early unit-test bootstrap), the + * {@link UnsatisfiedLinkError} is caught once and subsequent calls are + * silently skipped. + */ +public final class QGCNativeLogSink { + + /** Log-level ordinals — must match the C++ side mapping in AndroidLogSink.cc. */ + public static final int LEVEL_DEBUG = 0; + public static final int LEVEL_INFO = 1; + public static final int LEVEL_WARNING = 2; + public static final int LEVEL_ERROR = 3; + + private static volatile boolean sJniAvailable = true; + + private QGCNativeLogSink() { /* utility class */ } + + /** + * Forwards a log entry to native. + * + * @param level one of {@link #LEVEL_DEBUG}, {@link #LEVEL_INFO}, + * {@link #LEVEL_WARNING}, {@link #LEVEL_ERROR}. + * @param tag log tag (typically the calling class name). + * @param message log message. + */ + public static void log(final int level, final String tag, final String message) { + if (!sJniAvailable) { + return; + } + try { + nativeLog(level, tag, message); + } catch (final UnsatisfiedLinkError e) { + sJniAvailable = false; + // Intentionally silent: native library may not be loaded in tests. + } + } + + /** + * Native entry point registered by {@code AndroidLogSink.cc}. + * + * @param level log level ordinal (see {@link #LEVEL_DEBUG} etc.). + * @param tag log tag. + * @param message log message. + */ + public static native void nativeLog(int level, String tag, String message); +} diff --git a/android/src/org/mavlink/qgroundcontrol/QGCUsbId.java b/android/src/org/mavlink/qgroundcontrol/QGCUsbId.java deleted file mode 100644 index 433f4b94cb5a..000000000000 --- a/android/src/org/mavlink/qgroundcontrol/QGCUsbId.java +++ /dev/null @@ -1,85 +0,0 @@ -package org.mavlink.qgroundcontrol; - -public final class QGCUsbId { - - public static final int VENDOR_FTDI = 0x0403; - public static final int DEVICE_FTDI_FT232R = 0x6001; - public static final int DEVICE_FTDI_FT2232H = 0x6010; - public static final int DEVICE_FTDI_FT4232H = 0x6011; - public static final int DEVICE_FTDI_FT232H = 0x6014; - public static final int DEVICE_FTDI_FT231X = 0x6015; - - public static final int VENDOR_PX4 = 0x26AC; - public static final int DEVICE_PX4FMU_V1 = 0x0010; - public static final int DEVICE_PX4FMU_V2 = 0x0011; - public static final int DEVICE_PX4FMU_V3 = 0x0011; // V3 shares V2 USB PID - public static final int DEVICE_PX4FMU_V4 = 0x0012; - public static final int DEVICE_PX4FMU_V4PRO = 0x0013; - public static final int DEVICE_PX4FMU_V5 = 0x0032; - public static final int DEVICE_PX4FMU_V5X = 0x0033; - public static final int DEVICE_PX4FMU_V6C = 0x0038; - public static final int DEVICE_PX4FMU_V6U = 0x0036; - public static final int DEVICE_PX4FMU_V6X = 0x0035; - public static final int DEVICE_PX4FMU_V6XRT = 0x001D; - public static final int DEVICE_PX4MINDPX_V2 = 0x0030; - - public static final int VENDOR_UBLOX = 0x1546; - public static final int DEVICE_UBLOX_5 = 0x01a5; - public static final int DEVICE_UBLOX_6 = 0x01a6; - public static final int DEVICE_UBLOX_7 = 0x01a7; - public static final int DEVICE_UBLOX_8 = 0x01a8; - - public static final int VENDOR_OPENPILOT = 0x20A0; - public static final int DEVICE_REVOLUTION = 0x415E; - public static final int DEVICE_OPLINK = 0x415C; - public static final int DEVICE_SPARKY2 = 0x41D0; - public static final int DEVICE_CC3D = 0x415D; - - public static final int VENDOR_ARDUPILOT = 0x1209; - public static final int DEVICE_ARDUPILOT_CHIBIOS = 0x5740; - public static final int DEVICE_ARDUPILOT_CHIBIOS2 = 0x5741; - - public static final int VENDOR_DRAGONLINK = 0x1FC9; - public static final int DEVICE_DRAGONLINK = 0x0083; - - public static final int VENDOR_CUBEPILOT = 0x2DAE; - public static final int DEVICE_CUBE_BLACK = 0x1011; - public static final int DEVICE_CUBE_BLACK_BOOTLOADER = 0x1001; - public static final int DEVICE_CUBE_BLACK_PLUS = 0x1011; - public static final int DEVICE_CUBE_ORANGE = 0x1016; - public static final int DEVICE_CUBE_ORANGE2 = 0x1017; - public static final int DEVICE_CUBE_ORANGEPLUS = 0x1058; - public static final int DEVICE_CUBE_YELLOW_BOOTLOADER = 0x1002; - public static final int DEVICE_CUBE_YELLOW = 0x1012; - public static final int DEVICE_CUBE_PURPLE_BOOTLOADER = 0x1005; - public static final int DEVICE_CUBE_PURPLE = 0x1015; - - public static final int VENDOR_CUAV = 0x3163; - public static final int DEVICE_CUAV_NORA = 0x004C; - public static final int DEVICE_CUAV_X7PRO = 0x004C; // X7PRO shares NORA USB PID - - public static final int VENDOR_HOLYBRO = 0x3162; - public static final int DEVICE_PIXHAWK4 = 0x0047; - public static final int DEVICE_PH4_MINI = 0x0049; - public static final int DEVICE_DURANDAL = 0x004B; - - public static final int VENDOR_LASER_NAVIGATION = 0x27AC; - public static final int DEVICE_VRBRAIN_V51 = 0x1151; - public static final int DEVICE_VRBRAIN_V52 = 0x1152; - public static final int DEVICE_VRBRAIN_V54 = 0x1154; - public static final int DEVICE_VRCORE_V10 = 0x1910; - public static final int DEVICE_VRUBRAIN_V51 = 0x1351; - - private QGCUsbId() - { - throw new IllegalAccessError("Non-instantiable class"); - } - - public static boolean isSupportedFtdiProductId(final int productId) { - return productId == DEVICE_FTDI_FT232R - || productId == DEVICE_FTDI_FT2232H - || productId == DEVICE_FTDI_FT4232H - || productId == DEVICE_FTDI_FT232H - || productId == DEVICE_FTDI_FT231X; - } -} diff --git a/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialManager.java b/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialManager.java deleted file mode 100644 index 6d60f978b30d..000000000000 --- a/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialManager.java +++ /dev/null @@ -1,1520 +0,0 @@ -package org.mavlink.qgroundcontrol; - -import android.app.PendingIntent; -import android.content.*; -import android.hardware.usb.*; -import android.os.Build; -import android.os.Process; -import com.hoho.android.usbserial.driver.*; -import com.hoho.android.usbserial.util.*; - -import java.io.IOException; -import java.util.*; -import java.util.concurrent.*; -import java.util.concurrent.atomic.AtomicInteger; - -public class QGCUsbSerialManager { - private static final String TAG = QGCUsbSerialManager.class.getSimpleName(); - private static final String ACTION_USB_PERMISSION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION"; - // Sentinel values: BAD_DEVICE_ID (0) for invalid device IDs, - // getDeviceHandle() returns -1 for missing file descriptors. - private static final int BAD_DEVICE_ID = 0; - private static final int READ_BUF_SIZE = 2048; - private static final int MAX_NATIVE_CALLBACK_DATA_BYTES = 16 * 1024; - private static final String PORT_SUFFIX = "#p"; - private static final Object lifecycleLock = new Object(); - - private static UsbManager usbManager; - private static Context appContext; - private static PendingIntent usbPermissionIntent; - private static UsbSerialProber usbSerialProber; - private static boolean receiverRegistered; - - private static final List drivers = new CopyOnWriteArrayList<>(); - private static final ConcurrentHashMap deviceResourcesMap = new ConcurrentHashMap<>(); - private static final ConcurrentHashMap portAddressToResourceId = new ConcurrentHashMap<>(); - private static final ConcurrentHashMap resourceIdToPortAddress = new ConcurrentHashMap<>(); - private static final AtomicInteger nextResourceId = new AtomicInteger(1); - - interface NativeCallbacks { - void onDeviceHasDisconnected(long classPtr); - void onDeviceException(long classPtr, String message); - void onDeviceNewData(long classPtr, byte[] data); - } - - private static final class JniNativeCallbacks implements NativeCallbacks { - @Override - public void onDeviceHasDisconnected(final long classPtr) { - nativeDeviceHasDisconnected(classPtr); - } - - @Override - public void onDeviceException(final long classPtr, final String message) { - nativeDeviceException(classPtr, message); - } - - @Override - public void onDeviceNewData(final long classPtr, final byte[] data) { - nativeDeviceNewData(classPtr, data); - } - } - - private static volatile NativeCallbacks nativeCallbacks = new JniNativeCallbacks(); - - // Native methods - private static native void nativeDeviceHasDisconnected(final long classPtr); - private static native void nativeDeviceException(final long classPtr, final String message); - private static native void nativeDeviceNewData(final long classPtr, final byte[] data); - - static void setNativeCallbacksForTesting(final NativeCallbacks callbacks) { - nativeCallbacks = (callbacks != null) ? callbacks : new JniNativeCallbacks(); - } - - private static void emitDeviceHasDisconnected(final long classPtr) { - if (classPtr != 0) { - nativeCallbacks.onDeviceHasDisconnected(classPtr); - } - } - - private static void emitDeviceException(final long classPtr, final String message) { - if (classPtr != 0) { - nativeCallbacks.onDeviceException(classPtr, message); - } - } - - private static void emitDeviceNewData(final long classPtr, final byte[] data) { - if (classPtr != 0 && data != null && data.length > 0) { - nativeCallbacks.onDeviceNewData(classPtr, data); - } - } - - @SuppressWarnings("deprecation") - private static UsbDevice getUsbDevice(Intent intent) { - if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.TIRAMISU) { - return intent.getParcelableExtra(UsbManager.EXTRA_DEVICE, UsbDevice.class); - } - return intent.getParcelableExtra(UsbManager.EXTRA_DEVICE); - } - - private static DevicePortSpec parseDevicePortSpec(final String deviceName) { - if (deviceName == null || deviceName.isEmpty()) { - return new DevicePortSpec("", 0); - } - - final int split = deviceName.lastIndexOf(PORT_SUFFIX); - if (split <= 0) { - return new DevicePortSpec(deviceName, 0); - } - - final String baseName = deviceName.substring(0, split); - final String suffix = deviceName.substring(split + PORT_SUFFIX.length()); - try { - final int parsedIndex = Integer.parseInt(suffix); - return new DevicePortSpec(baseName, Math.max(0, parsedIndex)); - } catch (final NumberFormatException e) { - QGCLogger.w(TAG, "Invalid device port suffix in " + deviceName + ", defaulting to port 0"); - return new DevicePortSpec(deviceName, 0); - } - } - - static String getBaseDeviceNameForTesting(final String deviceName) { - return parseDevicePortSpec(deviceName).baseDeviceName; - } - - static int getPortIndexForTesting(final String deviceName) { - return parseDevicePortSpec(deviceName).portIndex; - } - - private static String buildPortDeviceName(final UsbDevice device, final int portIndex, final int portCount) { - final String baseName = device.getDeviceName(); - if (portCount <= 1 && portIndex == 0) { - return baseName; - } - return baseName + PORT_SUFFIX + portIndex; - } - - private static UsbSerialPort getPortFromDriver(final UsbSerialDriver driver, final int portIndex) { - if (driver == null) { - return null; - } - - final List ports = driver.getPorts(); - if (ports == null || ports.isEmpty()) { - return null; - } - - for (final UsbSerialPort port : ports) { - if (port.getPortNumber() == portIndex) { - return port; - } - } - - if (portIndex >= 0 && portIndex < ports.size()) { - return ports.get(portIndex); - } - - return null; - } - - private static int getOrCreateResourceId(final int physicalDeviceId, final int portIndex) { - final PortAddress address = new PortAddress(physicalDeviceId, portIndex); - final Integer existing = portAddressToResourceId.get(address); - if (existing != null) { - return existing; - } - - final int candidateId = nextResourceId.getAndUpdate(v -> (v >= Integer.MAX_VALUE) ? 1 : v + 1); - final Integer raced = portAddressToResourceId.putIfAbsent(address, candidateId); - final int resourceId = (raced != null) ? raced : candidateId; - if (raced == null) { - resourceIdToPortAddress.put(resourceId, address); - } - return resourceId; - } - - static int getOrCreateResourceIdForTesting(final int physicalDeviceId, final int portIndex) { - return getOrCreateResourceId(physicalDeviceId, portIndex); - } - - private static void removeResourceMapping(final int resourceId) { - final PortAddress address = resourceIdToPortAddress.remove(resourceId); - if (address != null) { - portAddressToResourceId.remove(address); - } - } - - static void removeResourceMappingForTesting(final int resourceId) { - removeResourceMapping(resourceId); - } - - static void resetResourceMappingsForTesting() { - portAddressToResourceId.clear(); - resourceIdToPortAddress.clear(); - nextResourceId.set(1); - } - - private static List findResourceIdsForPhysicalDevice(final int physicalDeviceId) { - final List ids = new ArrayList<>(); - for (Map.Entry entry : resourceIdToPortAddress.entrySet()) { - if (entry.getValue().physicalDeviceId == physicalDeviceId) { - ids.add(entry.getKey()); - } - } - return ids; - } - - private static void removeAllResourcesForPhysicalDevice(final int physicalDeviceId) { - for (final Integer resourceId : findResourceIdsForPhysicalDevice(physicalDeviceId)) { - close(resourceId); - } - } - - /** - * Encapsulates all resources associated with a USB device. - */ - private static class UsbDeviceResources { - UsbSerialDriver driver; - SerialInputOutputManager ioManager; - int fileDescriptor; - volatile long classPtr; - int portIndex; - int physicalDeviceId; - String baseDeviceName; - - UsbDeviceResources(final UsbSerialDriver driver, final int portIndex) { - this.driver = driver; - this.portIndex = portIndex; - if (driver != null && driver.getDevice() != null) { - this.physicalDeviceId = driver.getDevice().getDeviceId(); - this.baseDeviceName = driver.getDevice().getDeviceName(); - } - } - } - - private static final class PortAddress { - final int physicalDeviceId; - final int portIndex; - - PortAddress(final int physicalDeviceId, final int portIndex) { - this.physicalDeviceId = physicalDeviceId; - this.portIndex = portIndex; - } - - @Override - public boolean equals(final Object other) { - if (this == other) { - return true; - } - if (!(other instanceof PortAddress)) { - return false; - } - final PortAddress rhs = (PortAddress) other; - return (physicalDeviceId == rhs.physicalDeviceId) && (portIndex == rhs.portIndex); - } - - @Override - public int hashCode() { - return Objects.hash(physicalDeviceId, portIndex); - } - } - - private static final class DevicePortSpec { - final String baseDeviceName; - final int portIndex; - - DevicePortSpec(final String baseDeviceName, final int portIndex) { - this.baseDeviceName = baseDeviceName; - this.portIndex = Math.max(0, portIndex); - } - } - - /** - * Initializes the UsbSerialManager. Should be called once, typically from QGCActivity.onCreate(). - * - * @param context The application context. - */ - public static void initialize(Context context) { - synchronized (lifecycleLock) { - if (usbManager != null) { - return; - } - - appContext = context.getApplicationContext(); - usbManager = (UsbManager) appContext.getSystemService(Context.USB_SERVICE); - if (usbManager == null) { - QGCLogger.e(TAG, "Failed to get UsbManager"); - return; - } - - QGCFtdiDriver.initialize(appContext); - setupUsbPermissionIntent(appContext); - usbSerialProber = QGCUsbSerialProber.getQGCUsbSerialProber(); - registerUsbReceiver(appContext); - updateCurrentDrivers(); - } - } - - /** - * Cleans up resources by unregistering the BroadcastReceiver. - * Should be called when the manager is no longer needed, typically from QGCActivity.onDestroy(). - */ - public static void cleanup(Context context) { - synchronized (lifecycleLock) { - for (Integer deviceId : new ArrayList<>(deviceResourcesMap.keySet())) { - close(deviceId); - } - - final Context unregisterContext = (appContext != null) ? appContext : context; - try { - if (receiverRegistered) { - unregisterContext.unregisterReceiver(usbReceiver); - receiverRegistered = false; - QGCLogger.i(TAG, "BroadcastReceiver unregistered successfully."); - } - } catch (final IllegalArgumentException e) { - QGCLogger.w(TAG, "Receiver not registered: " + e.getMessage()); - } - - usbPermissionIntent = null; - usbSerialProber = null; - QGCFtdiDriver.cleanup(); - usbManager = null; - appContext = null; - drivers.clear(); - deviceResourcesMap.clear(); - portAddressToResourceId.clear(); - resourceIdToPortAddress.clear(); - nextResourceId.set(1); - } - } - - /** - * Sets up the PendingIntent for USB permission requests. - * - * @param context The application context. - */ - private static void setupUsbPermissionIntent(Context context) { - Intent permissionIntent = new Intent(ACTION_USB_PERMISSION).setPackage(context.getPackageName()); - int flags = PendingIntent.FLAG_UPDATE_CURRENT; - if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.M) { - flags |= PendingIntent.FLAG_IMMUTABLE; - } - usbPermissionIntent = PendingIntent.getBroadcast(context, 0, permissionIntent, flags); - } - - /** - * Registers the BroadcastReceiver to listen for USB-related events. - * - * @param context The application context. - */ - private static void registerUsbReceiver(Context context) { - IntentFilter filter = new IntentFilter(); - filter.addAction(UsbManager.ACTION_USB_DEVICE_ATTACHED); - filter.addAction(UsbManager.ACTION_USB_DEVICE_DETACHED); - filter.addAction(ACTION_USB_PERMISSION); - - try { - if (android.os.Build.VERSION.SDK_INT >= - android.os.Build.VERSION_CODES.TIRAMISU) { - int flags = Context.RECEIVER_NOT_EXPORTED; - context.registerReceiver(usbReceiver, filter, flags); - } else { - context.registerReceiver(usbReceiver, filter); - } - - receiverRegistered = true; - QGCLogger.i(TAG, "BroadcastReceiver registered successfully."); - } catch (Exception e) { - receiverRegistered = false; - QGCLogger.e(TAG, "Failed to register BroadcastReceiver", e); - } - } - - /** - * BroadcastReceiver to handle USB events. - */ - private static final BroadcastReceiver usbReceiver = new BroadcastReceiver() { - @Override - public void onReceive(Context context, Intent intent) { - final String action = intent.getAction(); - QGCLogger.i(TAG, "BroadcastReceiver USB action " + action); - - switch (action) { - case ACTION_USB_PERMISSION: - handleUsbPermission(intent); - break; - case UsbManager.ACTION_USB_DEVICE_DETACHED: - handleUsbDeviceDetached(intent); - break; - case UsbManager.ACTION_USB_DEVICE_ATTACHED: - handleUsbDeviceAttached(intent); - break; - default: - break; - } - - updateCurrentDrivers(); - } - }; - - /** - * Handles USB permission results. - * - * @param intent The intent containing permission data. - */ - private static void handleUsbPermission(final Intent intent) { - UsbDevice device = getUsbDevice(intent); - if (device != null) { - final int physicalDeviceId = device.getDeviceId(); - if (intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false)) { - QGCLogger.i(TAG, "Permission granted to " + device.getDeviceName()); - addOrUpdateDevice(device); - } else { - QGCLogger.i(TAG, "Permission denied for " + device.getDeviceName()); - for (final Integer resourceId : findResourceIdsForPhysicalDevice(physicalDeviceId)) { - final UsbDeviceResources resources = deviceResourcesMap.get(resourceId); - if (resources != null) { - emitDeviceException(resources.classPtr, "USB Permission Denied"); - } - } - } - } - } - - /** - * Handles USB device detachment events. - * - * @param intent The intent containing device data. - */ - private static void handleUsbDeviceDetached(final Intent intent) { - UsbDevice device = getUsbDevice(intent); - if (device != null) { - final int physicalDeviceId = device.getDeviceId(); - final List resourceIds = findResourceIdsForPhysicalDevice(physicalDeviceId); - for (final Integer resourceId : resourceIds) { - final UsbDeviceResources resources = deviceResourcesMap.get(resourceId); - if (resources == null) { - continue; - } - final long classPtr = resources.classPtr; - close(resourceId); - emitDeviceHasDisconnected(classPtr); - } - QGCLogger.i(TAG, "Device detached: " + device.getDeviceName()); - } - } - - /** - * Handles USB device attachment events. - * - * @param intent The intent containing device data. - */ - private static void handleUsbDeviceAttached(final Intent intent) { - UsbDevice device = getUsbDevice(intent); - if (device != null) { - addOrUpdateDevice(device); - } - } - - /** - * Adds a new device or updates an existing one. - * - * @param device The UsbDevice to add or update. - */ - private static void addOrUpdateDevice(UsbDevice device) { - UsbSerialDriver driver = findDriverByDeviceId(device.getDeviceId()); - if (driver != null) { - if (usbManager.hasPermission(device)) { - QGCLogger.i(TAG, "Already have permission to use device " + device.getDeviceName()); - addDriver(driver); - } else { - QGCLogger.i(TAG, "Requesting permission to use device " + device.getDeviceName()); - usbManager.requestPermission(device, usbPermissionIntent); - } - } - } - - /** - * Checks if a device name is valid (i.e., exists in the current driver list). - * - * @param name The device name to check. - * @return True if valid, false otherwise. - */ - public static boolean isDeviceNameValid(final String name) { - final DevicePortSpec spec = parseDevicePortSpec(name); - final UsbSerialDriver driver = findDriverByDeviceName(spec.baseDeviceName); - return getPortFromDriver(driver, spec.portIndex) != null; - } - - /** - * Checks if a device name is currently open. - * - * @param name The device name to check. - * @return True if open, false otherwise. - */ - public static boolean isDeviceNameOpen(final String name) { - final DevicePortSpec spec = parseDevicePortSpec(name); - final UsbSerialDriver driver = findDriverByDeviceName(spec.baseDeviceName); - if (driver == null) { - return false; - } - - final UsbSerialPort port = getPortFromDriver(driver, spec.portIndex); - return (port != null && port.isOpen()); - } - - /** - * Retrieves the device ID for a given device name. - * - * @param deviceName The device name. - * @return The device ID, or BAD_DEVICE_ID if not found. - */ - public static int getDeviceId(final String deviceName) { - final DevicePortSpec spec = parseDevicePortSpec(deviceName); - UsbSerialDriver driver = findDriverByDeviceName(spec.baseDeviceName); - if (driver == null) { - QGCLogger.w(TAG, "Attempt to get ID of unknown device " + deviceName); - return BAD_DEVICE_ID; - } - - if (getPortFromDriver(driver, spec.portIndex) == null) { - QGCLogger.w(TAG, "Attempt to get ID of unknown port index " + spec.portIndex + " for " + spec.baseDeviceName); - return BAD_DEVICE_ID; - } - - return getOrCreateResourceId(driver.getDevice().getDeviceId(), spec.portIndex); - } - - /** - * Retrieves the native device handle (file descriptor). - * - * @param deviceId The device ID. - * @return The device handle, or -1 if not found. - */ - public static int getDeviceHandle(final int deviceId) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - return (resources != null) ? resources.fileDescriptor : -1; - } - - /** - * Updates the current list of USB serial drivers by scanning connected devices. - */ - private static void updateCurrentDrivers() { - if (usbManager == null || usbSerialProber == null) { - QGCLogger.w(TAG, "USB serial manager not ready, skipping driver refresh"); - return; - } - - final List currentDrivers = usbSerialProber.findAllDrivers(usbManager); - removeStaleDrivers(currentDrivers); - if (!currentDrivers.isEmpty()) { - addNewDrivers(currentDrivers); - } - } - - /** - * Removes drivers that are no longer connected. - * Collects stale IDs first to avoid nested mutation of concurrent maps during iteration. - * - * @param currentDrivers The list of currently connected drivers. - */ - private static void removeStaleDrivers(final List currentDrivers) { - final List stalePhysicalIds = new ArrayList<>(); - drivers.removeIf(existingDriver -> { - final int existingPhysicalDeviceId = existingDriver.getDevice().getDeviceId(); - boolean found = currentDrivers.stream() - .anyMatch(currentDriver -> currentDriver.getDevice().getDeviceId() == existingDriver.getDevice().getDeviceId()); - - if (!found) { - stalePhysicalIds.add(existingPhysicalDeviceId); - QGCLogger.i(TAG, "Removed stale driver for device ID " + existingPhysicalDeviceId); - return true; - } - return false; - }); - - for (final int physicalDeviceId : stalePhysicalIds) { - removeAllResourcesForPhysicalDevice(physicalDeviceId); - } - } - - /** - * Adds new drivers that are not already in the driver list. - * - * @param currentDrivers The list of currently connected drivers. - */ - private static void addNewDrivers(final List currentDrivers) { - for (UsbSerialDriver newDriver : currentDrivers) { - boolean found = drivers.stream() - .anyMatch(existingDriver -> existingDriver.getDevice().getDeviceId() == newDriver.getDevice().getDeviceId()); - - if (!found) { - addDriver(newDriver); - } - } - } - - /** - * Adds a new USB serial driver to the driver list and requests permission if needed. - * - * @param newDriver The UsbSerialDriver to add. - */ - private static void addDriver(final UsbSerialDriver newDriver) { - UsbDevice device = newDriver.getDevice(); - String deviceName = device.getDeviceName(); - - final boolean alreadyTracked = drivers.stream() - .anyMatch(existingDriver -> existingDriver.getDevice().getDeviceId() == device.getDeviceId()); - if (alreadyTracked) { - QGCLogger.d(TAG, "Driver already tracked for device ID " + device.getDeviceId()); - return; - } - - drivers.add(newDriver); - QGCLogger.i(TAG, "Adding new driver for device ID " + device.getDeviceId() + ": " + deviceName); - - if (usbManager.hasPermission(device)) { - QGCLogger.i(TAG, "Already have permission to use device " + deviceName); - } else { - QGCLogger.i(TAG, "Requesting permission to use device " + deviceName); - usbManager.requestPermission(device, usbPermissionIntent); - } - } - - /** - * Finds a USB serial driver by its device ID. - * - * @param deviceId The device ID. - * @return The corresponding UsbSerialDriver or null if not found. - */ - private static UsbSerialDriver findDriverByDeviceId(final int deviceId) { - for (UsbSerialDriver driver : drivers) { - if (driver.getDevice().getDeviceId() == deviceId) { - return driver; - } - } - return null; - } - - /** - * Finds a USB serial driver by its device name. - * - * @param deviceName The device name. - * @return The corresponding UsbSerialDriver or null if not found. - */ - private static UsbSerialDriver findDriverByDeviceName(final String deviceName) { - for (UsbSerialDriver driver : drivers) { - if (driver.getDevice().getDeviceName().equals(deviceName)) { - return driver; - } - } - return null; - } - - /** - * Finds a USB serial port by its device ID. - * - * @param deviceId The device ID. - * @return The corresponding UsbSerialPort or null if not found. - */ - private static UsbSerialPort findPortByDeviceId(final int deviceId) { - if (deviceId == BAD_DEVICE_ID) { - QGCLogger.w(TAG, "Finding port failed for invalid Device ID " + deviceId); - return null; - } - - final UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null || resources.driver == null) { - QGCLogger.w(TAG, "No resources found for device ID " + deviceId); - return null; - } - - UsbSerialPort port = getPortFromDriver(resources.driver, resources.portIndex); - if (port == null) { - QGCLogger.w(TAG, "No port available on device ID " + deviceId + " at port index " + resources.portIndex); - return null; - } - - return port; - } - - private static UsbSerialPort getPortOrWarn(final int deviceId, final String operation) { - final UsbSerialPort port = findPortByDeviceId(deviceId); - if (port == null) { - QGCLogger.w(TAG, "Attempted to " + operation + " on a null port for device ID " + deviceId); - return null; - } - - return port; - } - - private static UsbSerialPort getOpenPortOrWarn(final int deviceId, final String operation) { - final UsbSerialPort port = getPortOrWarn(deviceId, operation); - if (port == null) { - return null; - } - - if (!port.isOpen()) { - QGCLogger.w(TAG, "Attempted to " + operation + " on a closed port for device ID " + deviceId); - return null; - } - - return port; - } - - /** - * Retrieves information about all available USB serial devices. - * - * @return An array of device information strings or null if no devices are available. - */ - public static String[] availableDevicesInfo() { - if (usbManager == null || drivers.isEmpty()) { - return null; - } - - final List deviceInfoList = new ArrayList<>(); - - for (final UsbSerialDriver driver : drivers) { - try { - final List ports = driver.getPorts(); - if (ports == null || ports.isEmpty()) { - continue; - } - - final int portCount = ports.size(); - for (final UsbSerialPort port : ports) { - final int portIndex = port.getPortNumber(); - final String exposedDeviceName = buildPortDeviceName(driver.getDevice(), portIndex, portCount); - final String deviceInfo = formatDeviceInfo(driver.getDevice(), exposedDeviceName); - deviceInfoList.add(deviceInfo); - } - } catch (SecurityException e) { - // On some integrated controllers like the Siyi UNIRC7 the usb device is used for video output. - // This in turn causes a security exception when trying to access device info without permission. - // We just eat the exception in these cases to prevent log spamming. - } - } - - return deviceInfoList.isEmpty() ? null : deviceInfoList.toArray(new String[0]); - } - - /** - * Formats device information into a standardized string. - * - * @param device The UsbDevice to format. - * @return A formatted string containing device information. - */ - private static String formatDeviceInfo(final UsbDevice device, final String exposedDeviceName) { - StringBuilder deviceInfo = new StringBuilder(); - deviceInfo.append(exposedDeviceName).append("\t") - .append(device.getProductName()).append("\t") - .append(device.getManufacturerName()).append("\t") - .append(device.getSerialNumber()).append("\t") - .append(device.getProductId()).append("\t") - .append(device.getVendorId()); - - QGCLogger.d(TAG, "Formatted Device Info: " + deviceInfo.toString()); - - return deviceInfo.toString(); - } - - /** - * Opens a USB serial device. - * - * @param deviceName The name of the device to open. - * @param classPtr A native pointer associated with the device. - * @return The device ID if successful, or BAD_DEVICE_ID if failed. - */ - public static int open(final String deviceName, final long classPtr) { - final DevicePortSpec spec = parseDevicePortSpec(deviceName); - UsbSerialDriver driver = findDriverByDeviceName(spec.baseDeviceName); - if (driver == null) { - QGCLogger.w(TAG, "Attempt to open unknown device " + deviceName); - return BAD_DEVICE_ID; - } - - UsbDevice device = driver.getDevice(); - final UsbSerialPort port = getPortFromDriver(driver, spec.portIndex); - if (port == null) { - QGCLogger.w(TAG, "No port " + spec.portIndex + " available on device " + deviceName); - return BAD_DEVICE_ID; - } - - final int physicalDeviceId = device.getDeviceId(); - final int resourceId = getOrCreateResourceId(physicalDeviceId, spec.portIndex); - if (!deviceResourcesMap.containsKey(resourceId)) { - deviceResourcesMap.put(resourceId, new UsbDeviceResources(driver, spec.portIndex)); - } - - final UsbDeviceResources resources = deviceResourcesMap.get(resourceId); - if (resources != null) { - resources.driver = driver; - resources.portIndex = spec.portIndex; - resources.physicalDeviceId = physicalDeviceId; - resources.baseDeviceName = device.getDeviceName(); - resources.classPtr = classPtr; - } - - if (!openDriver(port, device, resourceId, classPtr)) { - QGCLogger.e(TAG, "Failed to open driver for device " + deviceName); - emitDeviceException(classPtr, "Failed to open driver for device: " + deviceName); - final UsbDeviceResources failedResources = deviceResourcesMap.get(resourceId); - if (failedResources != null && failedResources.ioManager == null) { - deviceResourcesMap.remove(resourceId); - removeResourceMapping(resourceId); - } - return BAD_DEVICE_ID; - } - - if (!createIoManager(resourceId, port, classPtr)) { - try { - port.close(); - } catch (IOException e) { - QGCLogger.e(TAG, "Error closing port after IO manager failure", e); - } - deviceResourcesMap.remove(resourceId); - removeResourceMapping(resourceId); - return BAD_DEVICE_ID; - } - - QGCLogger.d(TAG, "Port open successful: " + port.toString()); - return resourceId; - } - - /** - * Opens the driver for a specific USB serial port. - * - * @param port The UsbSerialPort to open. - * @param device The UsbDevice associated with the port. - * @param deviceId The device ID. - * @param classPtr A native pointer associated with the device. - * @return True if successful, false otherwise. - */ - private static boolean openDriver(final UsbSerialPort port, final UsbDevice device, final int deviceId, final long classPtr) { - if (port == null) { - QGCLogger.w(TAG, "Null UsbSerialPort for device " + device.getDeviceName()); - emitDeviceException(classPtr, "No serial port available for device: " + device.getDeviceName()); - return false; - } - - if (port.isOpen()) { - QGCLogger.d(TAG, "Port already open for device ID " + deviceId); - return true; - } - - UsbDeviceConnection connection = usbManager.openDevice(device); - if (connection == null) { - QGCLogger.w(TAG, "No Usb Device Connection"); - emitDeviceException(classPtr, "No USB device connection for device: " + device.getDeviceName()); - return false; - } - - try { - port.open(connection); - } catch (final IOException ex) { - QGCLogger.e(TAG, "Error opening driver for device " + device.getDeviceName(), ex); - emitDeviceException(classPtr, "Error opening driver: " + ex.getMessage()); - connection.close(); - return false; - } - - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources != null) { - resources.fileDescriptor = connection.getFileDescriptor(); - } - - QGCLogger.d(TAG, "Port Driver open successful"); - return true; - } - - /** - * Creates and initializes the SerialInputOutputManager for a device. - * - * @param deviceId The device ID. - * @param port The UsbSerialPort to manage. - * @param classPtr A native pointer associated with the device. - * @return True if successful, false otherwise. - */ - private static boolean createIoManager(final int deviceId, final UsbSerialPort port, final long classPtr) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null) { - QGCLogger.w(TAG, "No resources found for device ID " + deviceId); - return false; - } - - if (resources.ioManager != null) { - QGCLogger.i(TAG, "IO Manager already exists for device ID " + deviceId); - return true; - } - - if (port == null) { - QGCLogger.w(TAG, "Cannot create USB serial IO manager with null port for device ID " + deviceId); - return false; - } - - QGCSerialListener listener = new QGCSerialListener(classPtr); - SerialInputOutputManager ioManager = new SerialInputOutputManager(port, listener); - - int readBufferSize = READ_BUF_SIZE; - final UsbEndpoint readEndpoint = port.getReadEndpoint(); - if (readEndpoint != null) { - readBufferSize = Math.max(readEndpoint.getMaxPacketSize(), READ_BUF_SIZE); - } - ioManager.setReadBufferSize(readBufferSize); - - QGCLogger.d(TAG, "Read Buffer Size: " + ioManager.getReadBufferSize()); - QGCLogger.d(TAG, "Write Buffer Size: " + ioManager.getWriteBufferSize()); - - try { - ioManager.setReadTimeout(0); - ioManager.setReadQueue(2); - ioManager.setWriteTimeout(0); - ioManager.setThreadPriority(Process.THREAD_PRIORITY_URGENT_AUDIO); - } catch (final IllegalStateException e) { - QGCLogger.e(TAG, "IO Manager configuration error:", e); - return false; - } - - resources.ioManager = ioManager; - QGCLogger.d(TAG, "Serial I/O Manager created for device ID " + deviceId); - return true; - } - - /** - * Starts the SerialInputOutputManager for a specific device. - * - * @param deviceId The device ID. - * @return True if successful or already running, false otherwise. - */ - public static boolean startIoManager(final int deviceId) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null) { - QGCLogger.w(TAG, "IO Manager not found for device ID " + deviceId); - return false; - } - - if (resources.ioManager == null) { - QGCLogger.w(TAG, "IO Manager not found for device ID " + deviceId); - return false; - } - - SerialInputOutputManager.State ioState = resources.ioManager.getState(); - if (ioState == SerialInputOutputManager.State.RUNNING) { - return true; - } - - try { - resources.ioManager.start(); - QGCLogger.d(TAG, "Serial I/O Manager started for device ID " + deviceId); - return true; - } catch (final IllegalStateException e) { - QGCLogger.e(TAG, "IO Manager Start exception:", e); - return false; - } - } - - /** - * Stops the SerialInputOutputManager for a specific device. - * - * @param deviceId The device ID. - * @return True if successful or already stopped, false otherwise. - */ - public static boolean stopIoManager(final int deviceId) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null) { - return false; - } - - if (resources.ioManager == null) { - return false; - } - - SerialInputOutputManager.State ioState = resources.ioManager.getState(); - if (ioState == SerialInputOutputManager.State.STOPPED || ioState == SerialInputOutputManager.State.STOPPING) { - return true; - } - - resources.ioManager.stop(); - QGCLogger.d(TAG, "Serial I/O Manager stopped for device ID " + deviceId); - return true; - } - - /** - * Checks if the SerialInputOutputManager is running for a specific device. - * - * @param deviceId The device ID. - * @return True if running, false otherwise. - */ - public static boolean ioManagerRunning(final int deviceId) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null) { - return false; - } - - if (resources.ioManager == null) { - return false; - } - - SerialInputOutputManager.State ioState = resources.ioManager.getState(); - return (ioState == SerialInputOutputManager.State.RUNNING); - } - - /** - * Closes the USB serial device. - * - * @param deviceId The device ID. - * @return True if successful, false otherwise. - */ - public static boolean close(int deviceId) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null) { - QGCLogger.d(TAG, "Close requested for already cleaned device ID " + deviceId); - removeResourceMapping(deviceId); - return true; - } - - UsbSerialPort port = findPortByDeviceId(deviceId); - if (port == null) { - QGCLogger.w(TAG, "Attempted to close a null port for device ID " + deviceId); - deviceResourcesMap.remove(deviceId); - removeResourceMapping(deviceId); - return true; - } - - if (!port.isOpen()) { - QGCLogger.d(TAG, "Close requested for already closed device ID " + deviceId); - deviceResourcesMap.remove(deviceId); - removeResourceMapping(deviceId); - return true; - } - - stopIoManager(deviceId); - - try { - port.close(); - QGCLogger.d(TAG, "Device " + deviceId + " closed successfully."); - return true; - } catch (final IOException ex) { - QGCLogger.e(TAG, "Error closing driver:", ex); - return false; - } finally { - deviceResourcesMap.remove(deviceId); - removeResourceMapping(deviceId); - } - } - - /** - * Writes data to the USB serial device. - * - * @param deviceId The device ID. - * @param data The byte array of data to write. - * @param length The number of bytes to write. - * @param timeoutMSec The timeout in milliseconds. - * @return The number of bytes written, or -1 if failed. - */ - public static int write(final int deviceId, final byte[] data, final int length, final int timeoutMSec) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "write"); - if (port == null) { - return -1; - } - - try { - port.write(data, length, timeoutMSec); - return length; - } catch (final SerialTimeoutException e) { - QGCLogger.e(TAG, "Write timeout occurred", e); - return -1; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error writing data", e); - return -1; - } - } - - /** - * Writes data asynchronously to the USB serial device. - * - * @param deviceId The device ID. - * @param data The byte array of data to write. - * @param timeoutMSec The timeout in milliseconds. - * @return The number of bytes written, or -1 if failed. - */ - public static int writeAsync(final int deviceId, final byte[] data, final int timeoutMSec) { - UsbDeviceResources resources = deviceResourcesMap.get(deviceId); - if (resources == null || resources.ioManager == null) { - QGCLogger.w(TAG, "IO Manager not found for device ID " + deviceId); - return -1; - } - - if (resources.ioManager.getReadTimeout() == 0) { - QGCLogger.w(TAG, "Read Timeout is 0 for writeAsync"); - } - - resources.ioManager.setWriteTimeout(timeoutMSec); - resources.ioManager.writeAsync(data); - - return data.length; - } - - /** - * Reads data from the USB serial device. - * - * @param deviceId The device ID. - * @param length The number of bytes to read. - * @param timeoutMs The timeout in milliseconds. - * @return A byte array containing the read data. - */ - public static byte[] read(final int deviceId, final int length, final int timeoutMs) { - if (timeoutMs < 200) { - QGCLogger.w(TAG, "Read with timeout less than recommended minimum of 200ms"); - } - - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "read"); - if (port == null) { - return new byte[]{}; - } - - byte[] buffer = new byte[length]; - int bytesRead = 0; - - try { - bytesRead = port.read(buffer, timeoutMs); - } catch (final IOException e) { - QGCLogger.e(TAG, "Error reading data", e); - } - - if (bytesRead < length) { - return Arrays.copyOf(buffer, bytesRead); - } - - return buffer; - } - - /** - * Sets the parameters on an open USB serial port. - * - * @param deviceId The device ID. - * @param baudRate The baud rate (e.g., 9600, 115200). - * @param dataBits The number of data bits (5, 6, 7, 8). - * @param stopBits The number of stop bits (1, 2). - * @param parity The parity setting (0: None, 1: Odd, 2: Even). - * @return True if successful, false otherwise. - */ - public static boolean setParameters(final int deviceId, final int baudRate, final int dataBits, final int stopBits, final int parity) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "set parameters"); - if (port == null) { - return false; - } - - try { - port.setParameters(baudRate, dataBits, stopBits, parity); - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error setting parameters" + ": " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error setting parameters", e); - return false; - } - - return true; - } - - private static boolean getControlLine(int deviceId, UsbSerialPort.ControlLine controlLine) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "get " + controlLine); - if (port == null) { - return false; - } - - if (!isControlLineSupported(port, controlLine)) { - QGCLogger.w(TAG, "Getting " + controlLine + " Not Supported"); - return false; - } - - try { - switch (controlLine) { - case CD: - return port.getCD(); - case CTS: - return port.getCTS(); - case DSR: - return port.getDSR(); - case DTR: - return port.getDTR(); - case RI: - return port.getRI(); - case RTS: - return port.getRTS(); - default: - return false; - } - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error getting " + controlLine + ": " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error getting " + controlLine, e); - return false; - } - } - - private static boolean setControlLine(int deviceId, UsbSerialPort.ControlLine controlLine, boolean on) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "set " + controlLine); - if (port == null) { - return false; - } - - if (!isControlLineSupported(port, controlLine)) { - QGCLogger.e(TAG, "Setting " + controlLine + " Not Supported"); - return false; - } - - try { - switch (controlLine) { - case DTR: - port.setDTR(on); - break; - case RTS: - port.setRTS(on); - break; - default: - QGCLogger.w(TAG, "Setting " + controlLine + " is not supported via this method."); - return false; - } - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error setting " + controlLine + ": " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error setting " + controlLine, e); - return false; - } - - return true; - } - - /** - * Checks if a specific control line is supported by the device. - * - * @param port The UsbSerialPort. - * @param controlLine The control line to check. - * @return True if supported, false otherwise. - */ - private static boolean isControlLineSupported(final UsbSerialPort port, final UsbSerialPort.ControlLine controlLine) { - EnumSet supportedControlLines; - - try { - supportedControlLines = port.getSupportedControlLines(); - } catch (final IOException e) { - QGCLogger.e(TAG, "Error getting supported control lines", e); - return false; - } - - return supportedControlLines.contains(controlLine); - } - - /** - * Retrieves the carrier detect (CD) flag from the device. - * - * @param deviceId The device ID. - * @return True if CD is active, false otherwise. - */ - public static boolean getCarrierDetect(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.CD); - } - - /** - * Retrieves the clear to send (CTS) flag from the device. - * - * @param deviceId The device ID. - * @return True if CTS is active, false otherwise. - */ - public static boolean getClearToSend(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.CTS); - } - - /** - * Retrieves the data set ready (DSR) flag from the device. - * - * @param deviceId The device ID. - * @return True if DSR is active, false otherwise. - */ - public static boolean getDataSetReady(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.DSR); - } - - /** - * Retrieves the data terminal ready (DTR) flag from the device. - * - * @param deviceId The device ID. - * @return True if DTR is active, false otherwise. - */ - public static boolean getDataTerminalReady(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.DTR); - } - - /** - * Sets the data terminal ready (DTR) flag on the device. - * - * @param deviceId The device ID. - * @param on True to set DTR, false to clear. - * @return True if successful, false otherwise. - */ - public static boolean setDataTerminalReady(final int deviceId, final boolean on) { - return setControlLine(deviceId, UsbSerialPort.ControlLine.DTR, on); - } - - /** - * Retrieves the request to send (RTS) flag from the device. - * - * @param deviceId The device ID. - * @return True if RTS is active, false otherwise. - */ - public static boolean getRequestToSend(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.RTS); - } - - /** - * Sets the request to send (RTS) flag on the device. - * - * @param deviceId The device ID. - * @param on True to set RTS, false to clear. - * @return True if successful, false otherwise. - */ - public static boolean setRequestToSend(final int deviceId, final boolean on) { - return setControlLine(deviceId, UsbSerialPort.ControlLine.RTS, on); - } - - /** - * Retrieves the ring indicator (RI) flag from the device. - * - * @param deviceId The device ID. - * @return True if RI is active, false otherwise. - */ - public static boolean getRingIndicator(final int deviceId) { - return getControlLine(deviceId, UsbSerialPort.ControlLine.RI); - } - - /** - * Retrieves the supported control lines from the device. - * - * @param deviceId The device ID. - * @return An array of control line ordinals. - */ - public static int[] getControlLines(final int deviceId) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "get control lines"); - if (port == null) { - return new int[]{}; - } - - EnumSet currentControlLines; - - try { - currentControlLines = port.getControlLines(); - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error getting control lines: " + e); - return new int[]{}; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error getting control lines", e); - return new int[]{}; - } - - int[] lines = currentControlLines.stream().mapToInt(UsbSerialPort.ControlLine::ordinal).toArray(); - return lines; - } - - /** - * Retrieves the current flow control setting from the device. - * - * @param deviceId The device ID. - * @return The flow control ordinal, or 0 if not supported. - */ - public static int getFlowControl(final int deviceId) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "get flow control"); - if (port == null) { - return 0; - } - - EnumSet supportedFlowControl = port.getSupportedFlowControl(); - if (supportedFlowControl.isEmpty()) { - QGCLogger.e(TAG, "Flow Control Not Supported"); - return 0; - } - - UsbSerialPort.FlowControl flowControl = port.getFlowControl(); - return flowControl.ordinal(); - } - - /** - * Sets the flow control setting on the device. - * - * @param deviceId The device ID. - * @param flowControl The flow control ordinal. - * @return True if successful, false otherwise. - */ - public static boolean setFlowControl(final int deviceId, final int flowControl) { - if (getFlowControl(deviceId) == flowControl) { - return true; - } - - if (flowControl < 0 || flowControl >= UsbSerialPort.FlowControl.values().length) { - QGCLogger.w(TAG, "Invalid flow control ordinal " + flowControl); - return false; - } - - UsbSerialPort.FlowControl flowControlEnum = UsbSerialPort.FlowControl.values()[flowControl]; - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "set flow control"); - if (port == null) { - return false; - } - - EnumSet supportedFlowControl = port.getSupportedFlowControl(); - if (!supportedFlowControl.contains(flowControlEnum)) { - QGCLogger.e(TAG, "Setting Flow Control Not Supported"); - return false; - } - - try { - port.setFlowControl(flowControlEnum); - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error setting Flow Control: " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error setting Flow Control", e); - return false; - } - - return true; - } - - /** - * Sets the break condition on the device. - * - * @param deviceId The device ID. - * @param on True to set break, false to clear break. - * @return True if successful, false otherwise. - */ - public static boolean setBreak(final int deviceId, final boolean on) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "set break"); - if (port == null) { - return false; - } - - try { - port.setBreak(on); - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error setting break condition: " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error setting break condition", e); - return false; - } - - return true; - } - - /** - * Purges the hardware buffers on the device. - * - * @param deviceId The device ID. - * @param input True to purge the input buffer. - * @param output True to purge the output buffer. - * @return True if successful, false otherwise. - */ - public static boolean purgeBuffers(final int deviceId, final boolean input, final boolean output) { - final UsbSerialPort port = getOpenPortOrWarn(deviceId, "purge buffers"); - if (port == null) { - return false; - } - - try { - port.purgeHwBuffers(input, output); - } catch (final UnsupportedOperationException e) { - QGCLogger.w(TAG, "Error purging buffers: " + e); - return false; - } catch (final IOException e) { - QGCLogger.e(TAG, "Error purging buffers", e); - return false; - } - - return true; - } - - /** - * Inner class to handle serial data callbacks. - */ - private static class QGCSerialListener implements SerialInputOutputManager.Listener { - private final long classPtr; - - public QGCSerialListener(long classPtr) { - this.classPtr = classPtr; - } - - @Override - public void onRunError(Exception e) { - QGCLogger.e(TAG, "Runner stopped.", e); - emitDeviceException(classPtr, "Runner stopped: " + e.getMessage()); - } - - @Override - public void onNewData(final byte[] data) { - if (!isValidData(data)) { - QGCLogger.w(TAG, "Invalid data received: " + Arrays.toString(data)); - return; - } - - if (data.length <= MAX_NATIVE_CALLBACK_DATA_BYTES) { - emitDeviceNewData(classPtr, data); - return; - } - - QGCLogger.w(TAG, "Large USB payload (" + data.length + " bytes), chunking before JNI callback"); - int offset = 0; - while (offset < data.length) { - final int end = Math.min(offset + MAX_NATIVE_CALLBACK_DATA_BYTES, data.length); - emitDeviceNewData(classPtr, Arrays.copyOfRange(data, offset, end)); - offset = end; - } - } - - private boolean isValidData(byte[] data) { - return ((data != null) && (data.length > 0)); - } - } -} diff --git a/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialProber.java b/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialProber.java deleted file mode 100644 index 852cdf8def0c..000000000000 --- a/android/src/org/mavlink/qgroundcontrol/QGCUsbSerialProber.java +++ /dev/null @@ -1,85 +0,0 @@ -package org.mavlink.qgroundcontrol; - -import com.hoho.android.usbserial.driver.CdcAcmSerialDriver; -import com.hoho.android.usbserial.driver.ProbeTable; -import com.hoho.android.usbserial.driver.UsbSerialProber; - -public class QGCUsbSerialProber { - - public static UsbSerialProber getQGCUsbSerialProber() { - return new UsbSerialProber(getQGCProbeTable()); - } - - public static ProbeTable getQGCProbeTable() { - final ProbeTable probeTable = UsbSerialProber.getDefaultProbeTable(); - - // FTDI (D2XX-backed adapter). When unavailable, keep default FTDI probing. - if (QGCFtdiDriver.isAvailable()) { - probeTable.addProduct(QGCUsbId.VENDOR_FTDI, QGCUsbId.DEVICE_FTDI_FT232R, QGCFtdiSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_FTDI, QGCUsbId.DEVICE_FTDI_FT2232H, QGCFtdiSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_FTDI, QGCUsbId.DEVICE_FTDI_FT4232H, QGCFtdiSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_FTDI, QGCUsbId.DEVICE_FTDI_FT232H, QGCFtdiSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_FTDI, QGCUsbId.DEVICE_FTDI_FT231X, QGCFtdiSerialDriver.class); - } - - // PX4 - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V1, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V2, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V4, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V4PRO, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V5, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V5X, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V6C, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V6U, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V6X, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4FMU_V6XRT, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_PX4, QGCUsbId.DEVICE_PX4MINDPX_V2, CdcAcmSerialDriver.class); - - // u-blox GPS - probeTable.addProduct(QGCUsbId.VENDOR_UBLOX, QGCUsbId.DEVICE_UBLOX_5, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_UBLOX, QGCUsbId.DEVICE_UBLOX_6, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_UBLOX, QGCUsbId.DEVICE_UBLOX_7, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_UBLOX, QGCUsbId.DEVICE_UBLOX_8, CdcAcmSerialDriver.class); - - // OpenPilot - probeTable.addProduct(QGCUsbId.VENDOR_OPENPILOT, QGCUsbId.DEVICE_REVOLUTION, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_OPENPILOT, QGCUsbId.DEVICE_OPLINK, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_OPENPILOT, QGCUsbId.DEVICE_SPARKY2, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_OPENPILOT, QGCUsbId.DEVICE_CC3D, CdcAcmSerialDriver.class); - - // ArduPilot - probeTable.addProduct(QGCUsbId.VENDOR_ARDUPILOT, QGCUsbId.DEVICE_ARDUPILOT_CHIBIOS, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_ARDUPILOT, QGCUsbId.DEVICE_ARDUPILOT_CHIBIOS2, CdcAcmSerialDriver.class); - - // DragonLink - probeTable.addProduct(QGCUsbId.VENDOR_DRAGONLINK, QGCUsbId.DEVICE_DRAGONLINK, CdcAcmSerialDriver.class); - - // CubePilot - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_BLACK, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_BLACK_BOOTLOADER, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_ORANGE, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_ORANGE2, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_ORANGEPLUS, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_YELLOW_BOOTLOADER, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_YELLOW, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_PURPLE_BOOTLOADER, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_CUBEPILOT, QGCUsbId.DEVICE_CUBE_PURPLE, CdcAcmSerialDriver.class); - - // CUAV - probeTable.addProduct(QGCUsbId.VENDOR_CUAV, QGCUsbId.DEVICE_CUAV_NORA, CdcAcmSerialDriver.class); - - // Holybro - probeTable.addProduct(QGCUsbId.VENDOR_HOLYBRO, QGCUsbId.DEVICE_PIXHAWK4, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_HOLYBRO, QGCUsbId.DEVICE_PH4_MINI, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_HOLYBRO, QGCUsbId.DEVICE_DURANDAL, CdcAcmSerialDriver.class); - - // Laser Navigation (VRBrain) - probeTable.addProduct(QGCUsbId.VENDOR_LASER_NAVIGATION, QGCUsbId.DEVICE_VRBRAIN_V51, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_LASER_NAVIGATION, QGCUsbId.DEVICE_VRBRAIN_V52, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_LASER_NAVIGATION, QGCUsbId.DEVICE_VRBRAIN_V54, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_LASER_NAVIGATION, QGCUsbId.DEVICE_VRCORE_V10, CdcAcmSerialDriver.class); - probeTable.addProduct(QGCUsbId.VENDOR_LASER_NAVIGATION, QGCUsbId.DEVICE_VRUBRAIN_V51, CdcAcmSerialDriver.class); - - return probeTable; - } -} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePump.java b/android/src/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePump.java new file mode 100644 index 000000000000..4812db054483 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePump.java @@ -0,0 +1,250 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; + +import java.util.concurrent.LinkedBlockingQueue; +import java.util.concurrent.BlockingQueue; +import java.util.concurrent.TimeUnit; +import java.util.concurrent.atomic.AtomicBoolean; + +/** + * Async write pump that decouples the JNI write thread from the actual USB transfer. + * The caller's submit() enqueues a buffer and returns immediately (modulo backpressure + * + optional wire-rate throttling); N worker threads drain the queue via a pluggable + * {@link WriteOp}. + * + *

Two transfer strategies are supported via factory methods:

+ *
    + *
  • {@link #forBulkTransfer}: N=4 workers calling {@link UsbDeviceConnection#bulkTransfer}. + * Linux usbfs queues multiple URBs per endpoint when submitted from different threads, + * so this pipelines without touching {@link android.hardware.usb.UsbRequest} — and + * therefore without racing mik3y's read path on the shared per-connection waiter. + * Used for CDC-ACM, CP210x, CH34x, and mik3y-mode FTDI.
  • + *
  • {@link #forD2xx}: N=1 worker calling D2XX's {@code FT_Device.write(wait=true)}. + * D2XX claims the FTDI interface exclusively on its own internal connection, so + * parallel-connection bulkTransfer fails kernel-side; the only viable D2XX write + * path is D2XX's own API, which is single-URB and must be serialized. The worker + * blocks at wire rate per call; the JNI thread is shielded by the queue + token + * bucket. Used for QGCFtdiSerialDriver (D2XX-backed) FTDI ports.
  • + *
+ * + *

Threading: caller invokes {@link #submit} from the JNI write thread (single-producer); + * worker threads pull from a bounded queue. submit() blocks on queue full up to + * SUBMIT_TIMEOUT_MS — that's the backpressure mechanism — with the same hard cap defending + * the owner thread against pump stalls. When {@link #setBaudRate} is non-zero, submit() also + * blocks on a token bucket refilling at baud/10 bytes/sec — required for D2XX FTDI ports + * because the chip's 256 B hardware TX FIFO overruns silently above wire rate.

+ */ +final class AsyncUsbWritePump { + + private static final String TAG = AsyncUsbWritePump.class.getSimpleName(); + + private static final int BULK_WORKER_THREADS = 4; + private static final int D2XX_WORKER_THREADS = 1; + /** Hard cap for a single submit; matches C++ {@code MAX_SYNC_WRITE_CHUNK}. */ + private static final int MAX_SUBMIT_BYTES = 16 * 1024; + /** Per-write kernel/D2XX timeout. Long enough that a healthy cube never hits it. */ + private static final int WRITE_TIMEOUT_MS = 1000; + /** Max time submit() blocks for queue space before returning -1; defends owner thread against pump stalls. */ + private static final long SUBMIT_TIMEOUT_MS = 2000L; + /** Max time to wait for worker threads to drain on close. */ + private static final long CLOSE_JOIN_MS = 500L; + /** Token bucket capacity in bytes; ~FT232R TX FIFO (256 B) + completion-latency margin. */ + private static final long BUCKET_CAPACITY_BYTES = 512L; + + /** Pluggable write strategy. Returns bytes written, or negative on failure. */ + @FunctionalInterface + interface WriteOp { + int write(byte[] buf, int length, int timeoutMs) throws Exception; + } + + /** Queue item carrying caller-owned buffer + a release callback the worker fires + * once the write completes (success or failure). Keeps the pump zero-allocation + * on the hot path — the byte[] lives in the caller's pool, not in pump-owned + * scratch space. */ + private static final class WriteTask { + final byte[] buf; + final int length; + final Runnable onComplete; + WriteTask(final byte[] buf, final int length, final Runnable onComplete) { + this.buf = buf; + this.length = length; + this.onComplete = onComplete; + } + } + + private final WriteOp writeOp; + private final BlockingQueue queue; + private final Thread[] workers; + private final AtomicBoolean closed = new AtomicBoolean(false); + + private volatile int wireBaudBitsPerSec = 0; + private final Object bucketLock = new Object(); + private long bucketTokensBytes; + private long bucketLastRefillNanos; + + /** Pump using bulkTransfer with 4 parallel workers. For devices whose interface is owned + * by our {@link UsbDeviceConnection} (CDC-ACM, CP210x, CH34x, mik3y FTDI). */ + static AsyncUsbWritePump forBulkTransfer(final UsbDeviceConnection connection, + final UsbEndpoint writeEndpoint) { + return new AsyncUsbWritePump( + (buf, len, timeoutMs) -> connection.bulkTransfer(writeEndpoint, buf, len, timeoutMs), + BULK_WORKER_THREADS, "bulk"); + } + + /** Pump using a D2XX write op with a single worker. The op must call + * {@code FT_Device.write(buf, len, true, timeoutMs)} on D2XX's own connection — only + * viable D2XX write path. wait=true blocks the worker at wire rate. */ + static AsyncUsbWritePump forD2xx(final WriteOp d2xxWriteOp) { + return new AsyncUsbWritePump(d2xxWriteOp, D2XX_WORKER_THREADS, "d2xx"); + } + + private AsyncUsbWritePump(final WriteOp writeOp, final int workerCount, final String mode) { + this.writeOp = writeOp; + this.queue = new LinkedBlockingQueue<>(workerCount); + this.workers = new Thread[workerCount]; + for (int i = 0; i < workerCount; i++) { + final Thread t = new Thread(this::runWorker, "QGCAsyncUsbWritePump-" + mode + "-" + i); + t.setDaemon(true); + workers[i] = t; + t.start(); + } + } + + /** Enables wire-rate throttling. baud=0 disables. Call after setParameters succeeds. */ + void setBaudRate(final int baud) { + synchronized (bucketLock) { + wireBaudBitsPerSec = baud; + bucketTokensBytes = BUCKET_CAPACITY_BYTES; + bucketLastRefillNanos = System.nanoTime(); + bucketLock.notifyAll(); + } + } + + /** Ownership-transfer submit. Pump takes ownership of {@code data} until the worker + * fires {@code onComplete}; the caller MUST NOT touch the buffer between submit + * returning and onComplete running. onComplete is invoked exactly once on every + * code path — including all -1 returns — so callers can safely use it for pool + * release / refcount decrement. The byte[] is enqueued as-is: no copy. + *

Returns {@code length} on successful enqueue, -1 on closed / invalid / + * submit timeout / throttle starvation. Blocks until the queue has space (and + * tokens, if throttled).

*/ + int submit(final byte[] data, final int length, final Runnable onComplete) { + if (closed.get()) { + onComplete.run(); + return -1; + } + if (length <= 0 || length > MAX_SUBMIT_BYTES || data == null || data.length < length) { + QGCLogger.w(TAG, "submit invalid length " + length); + onComplete.run(); + return -1; + } + if (wireBaudBitsPerSec > 0 && !drainTokens(length)) { + QGCLogger.w(TAG, "submit throttle timeout (len=" + length + ", baud=" + wireBaudBitsPerSec + ")"); + onComplete.run(); + return -1; + } + final boolean offered; + try { + offered = queue.offer(new WriteTask(data, length, onComplete), + SUBMIT_TIMEOUT_MS, TimeUnit.MILLISECONDS); + } catch (final InterruptedException e) { + Thread.currentThread().interrupt(); + onComplete.run(); + return -1; + } + if (!offered) { + QGCLogger.w(TAG, "submit timeout — pump queue full"); + onComplete.run(); + return -1; + } + return length; + } + + /** Token-bucket gate. Refill = baud/10 bytes/sec (8N1). */ + private boolean drainTokens(final int bytes) { + final long deadlineNanos = System.nanoTime() + SUBMIT_TIMEOUT_MS * 1_000_000L; + synchronized (bucketLock) { + while (true) { + final long now = System.nanoTime(); + final int baud = wireBaudBitsPerSec; + if (baud <= 0) return true; + final long elapsed = now - bucketLastRefillNanos; + if (elapsed > 0) { + final long refilled = elapsed * baud / 10L / 1_000_000_000L; + if (refilled > 0) { + bucketTokensBytes = Math.min(BUCKET_CAPACITY_BYTES, bucketTokensBytes + refilled); + bucketLastRefillNanos = now; + } + } + if (bucketTokensBytes >= bytes) { + bucketTokensBytes -= bytes; + return true; + } + if (now >= deadlineNanos) return false; + final long needBytes = bytes - bucketTokensBytes; + long waitNanos = needBytes * 10L * 1_000_000_000L / baud; + if (waitNanos > deadlineNanos - now) waitNanos = deadlineNanos - now; + if (waitNanos < 1_000_000L) waitNanos = 1_000_000L; + try { + bucketLock.wait(waitNanos / 1_000_000L, (int) (waitNanos % 1_000_000L)); + } catch (final InterruptedException e) { + Thread.currentThread().interrupt(); + return false; + } + if (closed.get()) return false; + } + } + } + + private void runWorker() { + while (!closed.get()) { + final WriteTask task; + try { + task = queue.poll(250, TimeUnit.MILLISECONDS); + } catch (final InterruptedException e) { + Thread.currentThread().interrupt(); + return; + } + if (task == null) continue; + try { + final int n = writeOp.write(task.buf, task.length, WRITE_TIMEOUT_MS); + if (n < 0 && !closed.get()) { + QGCLogger.w(TAG, "write failed (n=" + n + ", len=" + task.length + ")"); + } + } catch (final Throwable t) { + if (!closed.get()) { + QGCLogger.w(TAG, "write threw: " + t); + } + } finally { + // Always release — the buffer is caller-owned and must return to its pool / + // get decref'd whether the write succeeded, failed, or threw. + try { task.onComplete.run(); } + catch (final Throwable t) { QGCLogger.w(TAG, "onComplete threw: " + t); } + } + } + } + + void close() { + if (!closed.compareAndSet(false, true)) return; + synchronized (bucketLock) { bucketLock.notifyAll(); } + for (final Thread t : workers) t.interrupt(); + for (final Thread t : workers) { + try { + t.join(CLOSE_JOIN_MS); + } catch (final InterruptedException e) { + Thread.currentThread().interrupt(); + } + } + // Drain any tasks the workers didn't pull before exiting and fire their + // onComplete so caller-owned buffers go back to their pools. Without this + // the pool slowly leaks on every close(). + for (WriteTask task; (task = queue.poll()) != null; ) { + try { task.onComplete.run(); } + catch (final Throwable t) { QGCLogger.w(TAG, "onComplete threw on close: " + t); } + } + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/BoundedPool.java b/android/src/org/mavlink/qgroundcontrol/serial/BoundedPool.java new file mode 100644 index 000000000000..fec7671d2c34 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/BoundedPool.java @@ -0,0 +1,41 @@ +package org.mavlink.qgroundcontrol.serial; + +import java.util.concurrent.ArrayBlockingQueue; +import java.util.function.IntFunction; +import java.util.function.ToIntFunction; + +/** + * Bounded object pool with size-aware borrow. + * + *

{@link ArrayBlockingQueue#offer} is atomic and silently drops on overflow; + * {@link ArrayBlockingQueue#poll} returns null on empty. Callers always get a + * usable item — undersized poll results and empty-pool conditions both fall + * through to the {@code allocator}.

+ * + *

Note: ConcurrentLinkedQueue's {@code size()+offer()} is not atomic and + * lets the pool grow past CAP under concurrent returns; ArrayBlockingQueue's + * bounded offer is the correct primitive here.

+ */ +final class BoundedPool { + + private final ArrayBlockingQueue pool; + private final IntFunction allocator; + private final ToIntFunction sizer; + + BoundedPool(final int capacity, final IntFunction allocator, final ToIntFunction sizer) { + this.pool = new ArrayBlockingQueue<>(capacity); + this.allocator = allocator; + this.sizer = sizer; + } + + /** Returns a pooled item with size >= {@code minSize}, or a freshly-allocated one. */ + T borrow(final int minSize) { + final T item = pool.poll(); + return (item != null && sizer.applyAsInt(item) >= minSize) ? item : allocator.apply(minSize); + } + + /** Returns an item to the pool. Silently dropped on overflow. */ + void release(final T item) { + pool.offer(item); + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/NativeDataEmitter.java b/android/src/org/mavlink/qgroundcontrol/serial/NativeDataEmitter.java new file mode 100644 index 000000000000..c7b9067a8296 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/NativeDataEmitter.java @@ -0,0 +1,46 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.mavlink.qgroundcontrol.serial.SerialConstants.DIRECT_BUFFER_POOL_CAP; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.MAX_NATIVE_CALLBACK_DATA_BYTES; + +import java.nio.ByteBuffer; + +/** + * Owns the pooled direct ByteBuffer used to ferry USB read data to native code. + * + *

One unavoidable memcpy: upstream delivers byte[] on the Java heap; we copy + * into a pooled direct buffer so C++ can use GetDirectBufferAddress with no + * second copy. The buffer is returned to the pool the moment {@link NativeDataSink#emit} + * returns — callers must consume it synchronously.

+ */ +final class NativeDataEmitter { + + @FunctionalInterface + interface NativeDataSink { + void emit(long token, ByteBuffer data, int length); + } + + // Pool always allocates max-sized buffers so any pooled item satisfies any borrow. + private final BoundedPool bufferPool = new BoundedPool<>( + DIRECT_BUFFER_POOL_CAP, + capacity -> ByteBuffer.allocateDirect(MAX_NATIVE_CALLBACK_DATA_BYTES), + ByteBuffer::capacity); + + private final NativeDataSink sink; + + NativeDataEmitter(final NativeDataSink sink) { + this.sink = sink; + } + + void emit(final long nativeToken, final byte[] data, final int offset, final int length) { + final ByteBuffer buf = bufferPool.borrow(length); + buf.clear(); + buf.put(data, offset, length); + buf.flip(); + try { + sink.emit(nativeToken, buf, length); + } finally { + bufferPool.release(buf); + } + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/QGCFtdiSerialDriver.java b/android/src/org/mavlink/qgroundcontrol/serial/QGCFtdiSerialDriver.java new file mode 100644 index 000000000000..efa5f8f86968 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/QGCFtdiSerialDriver.java @@ -0,0 +1,637 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.content.Context; +import android.hardware.usb.UsbConstants; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbInterface; +import com.ftdi.j2xx.D2xxManager; +import com.ftdi.j2xx.FT_Device; +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialPort; + +import java.io.IOException; +import java.util.ArrayList; +import java.util.Collections; +import java.util.EnumSet; +import java.util.List; +import java.util.Map; +import java.util.concurrent.atomic.AtomicReference; + +public final class QGCFtdiSerialDriver implements UsbSerialDriver { + + private static final String TAG = QGCFtdiSerialDriver.class.getSimpleName(); + + // FTDI VID + the PIDs this D2XX driver claims. usb-serial-for-android's stock + // FtdiSerialDriver also handles these PIDs in VCP mode; the prober swaps to this + // class when D2XX is available so devices in D2XX-mode firmware work. + private static final int VENDOR_FTDI = 0x0403; + private static final int DEVICE_FTDI_FT232R = 0x6001; + private static final int DEVICE_FTDI_FT2232H = 0x6010; + private static final int DEVICE_FTDI_FT4232H = 0x6011; + private static final int DEVICE_FTDI_FT232H = 0x6014; + private static final int DEVICE_FTDI_FT231X = 0x6015; + + // D2XX is OFF by default. Regression: on Android 14 / OneUI 6 (QGC issue #14146), + // D2XX.createDeviceInfoList() enumerates the device and serial matches succeed, + // but D2xxManager.openByUsbDevice() then fails — so canOpenViaD2XX() reports the + // device as openable when it isn't, and the prober commits to a driver that + // cannot open. VCP-mode FtdiSerialDriver works for the same chips and already + // gets the 1ms latency-timer drop via vendor control transfer in + // UsbSerialLifecycle.openDriver (FTDI_SIO_SET_LATENCY). Re-enable for hardware + // validation, not for shipping. + public static final boolean ENABLE_D2XX = false; + + /** + * D2XX manager lifecycle — shared across all ports on all FTDI devices. + * The manager and its app Context are published together via a single + * {@link AtomicReference} so open() sees a consistent (manager, context) + * pair even if cleanup() races in from another thread. + */ + private static final class D2xxHandle { + final Context appContext; + final D2xxManager manager; + D2xxHandle(final Context appContext, final D2xxManager manager) { + this.appContext = appContext; + this.manager = manager; + } + } + + private static final AtomicReference sD2xx = new AtomicReference<>(); + + private final UsbDevice _device; + private final List _ports; + + public QGCFtdiSerialDriver(final UsbDevice device) { + _device = device; + + final int interfaceCount = device.getInterfaceCount(); + if (interfaceCount <= 0) { + _ports = Collections.emptyList(); + return; + } + final List ports = new ArrayList<>(interfaceCount); + for (int i = 0; i < interfaceCount; i++) { + ports.add(new QGCFtdiSerialPort(this, device, i)); + } + + _ports = Collections.unmodifiableList(ports); + } + + public static void initialize(final Context context) { + final Context appContext = context.getApplicationContext(); + D2xxManager manager = null; + try { + manager = D2xxManager.getInstance(appContext); + } catch (D2xxManager.D2xxException e) { + QGCLogger.w(TAG, "D2XX manager unavailable: " + e.getMessage()); + } catch (Throwable t) { + QGCLogger.w(TAG, "D2XX manager unavailable: " + t.getMessage()); + } + sD2xx.set((manager != null) ? new D2xxHandle(appContext, manager) : null); + } + + public static void cleanup() { + sD2xx.set(null); + } + + public static boolean isAvailable() { + return sD2xx.get() != null; + } + + public static boolean isFtdiDevice(final UsbDevice device) { + if (device == null || device.getVendorId() != VENDOR_FTDI) return false; + final int pid = device.getProductId(); + return pid == DEVICE_FTDI_FT232R || pid == DEVICE_FTDI_FT2232H + || pid == DEVICE_FTDI_FT4232H || pid == DEVICE_FTDI_FT232H + || pid == DEVICE_FTDI_FT231X; + } + + public static Map getSupportedDevices() { + return Collections.singletonMap(VENDOR_FTDI, new int[] { + DEVICE_FTDI_FT232R, + DEVICE_FTDI_FT2232H, + DEVICE_FTDI_FT4232H, + DEVICE_FTDI_FT232H, + DEVICE_FTDI_FT231X, + }); + } + + /** + * Returns true only if the D2XX library currently enumerates {@code device}. + * Generic FT232R USB-TTL adapters present in VCP mode and are not enumerated + * by D2XX — those must fall through to the stock {@code FtdiSerialDriver}. + */ + public static boolean canOpenViaD2XX(final UsbDevice device) { + if (!isFtdiDevice(device)) return false; + final D2xxHandle h = sD2xx.get(); + if (h == null) return false; + try { + final int count = h.manager.createDeviceInfoList(h.appContext); + if (count <= 0) return false; + final D2xxManager.FtDeviceInfoListNode[] nodes = new D2xxManager.FtDeviceInfoListNode[count]; + final int got = h.manager.getDeviceInfoList(count, nodes); + if (got <= 0) return false; + final String deviceSerial = device.getSerialNumber(); + for (int i = 0; i < got; i++) { + final D2xxManager.FtDeviceInfoListNode node = nodes[i]; + if (node == null) continue; + if (deviceSerial != null && deviceSerial.equals(node.serialNumber)) return true; + } + } catch (Throwable t) { + QGCLogger.w(TAG, "canOpenViaD2XX check failed: " + t.getMessage()); + } + return false; + } + + @Override + public UsbDevice getDevice() { + return _device; + } + + @Override + public List getPorts() { + return _ports; + } + + private static byte toD2xxDataBits(final int dataBits) { + return (dataBits == 7) ? D2xxManager.FT_DATA_BITS_7 : D2xxManager.FT_DATA_BITS_8; + } + + private static byte toD2xxStopBits(final int stopBits) { + if (stopBits == UsbSerialPort.STOPBITS_2) { + return D2xxManager.FT_STOP_BITS_2; + } + return D2xxManager.FT_STOP_BITS_1; + } + + private static byte toD2xxParity(final int parity) { + switch (parity) { + case UsbSerialPort.PARITY_ODD: + return D2xxManager.FT_PARITY_ODD; + case UsbSerialPort.PARITY_EVEN: + return D2xxManager.FT_PARITY_EVEN; + case UsbSerialPort.PARITY_MARK: + return D2xxManager.FT_PARITY_MARK; + case UsbSerialPort.PARITY_SPACE: + return D2xxManager.FT_PARITY_SPACE; + case UsbSerialPort.PARITY_NONE: + default: + return D2xxManager.FT_PARITY_NONE; + } + } + + private static short toD2xxFlowControl(final UsbSerialPort.FlowControl flowControl) { + if (flowControl == UsbSerialPort.FlowControl.RTS_CTS) { + return D2xxManager.FT_FLOW_RTS_CTS; + } + if (flowControl == UsbSerialPort.FlowControl.DTR_DSR) { + return D2xxManager.FT_FLOW_DTR_DSR; + } + if (flowControl == UsbSerialPort.FlowControl.XON_XOFF) { + return D2xxManager.FT_FLOW_XON_XOFF; + } + return D2xxManager.FT_FLOW_NONE; + } + + /** Package-visible for {@code UsbSerialLifecycle}'s baud-listener wiring. */ + static final class QGCFtdiSerialPort implements UsbSerialPort { + private final QGCFtdiSerialDriver _driver; + private final UsbDevice _device; + private final int _portNumber; + + private UsbDeviceConnection _connection; + private FT_Device _ftDevice; + private FlowControl _flowControl = FlowControl.NONE; + private boolean _dtr; + /** Current configured baud — exposed for the write pump's wire-rate throttle. */ + private volatile int _currentBaudRate = 9600; + private volatile java.util.function.IntConsumer _baudListener; + private boolean _rts; + private int _readQueueBufferCount; + private int _readQueueBufferSize; + + QGCFtdiSerialPort(final QGCFtdiSerialDriver driver, final UsbDevice device, final int portNumber) { + _driver = driver; + _device = device; + _portNumber = portNumber; + } + + @Override + public UsbSerialDriver getDriver() { + return _driver; + } + + @Override + public UsbDevice getDevice() { + return _device; + } + + @Override + public int getPortNumber() { + return _portNumber; + } + + // D2XX library performs I/O internally; the bulk endpoints are exposed only so the + // I/O manager can size its read buffer via getMaxPacketSize(). We resolve lazily on + // demand and never fail port open() over an unresolved endpoint. + @Override + public UsbEndpoint getWriteEndpoint() { + return null; + } + + @Override + public UsbEndpoint getReadEndpoint() { + if (!isOpen()) { + return null; + } + final int interfaceCount = _device.getInterfaceCount(); + final int interfaceIndex = (_portNumber < interfaceCount) ? _portNumber + : (interfaceCount == 1 ? 0 : -1); + if (interfaceIndex < 0) { + return null; + } + final UsbInterface usbInterface = _device.getInterface(interfaceIndex); + for (int e = 0; e < usbInterface.getEndpointCount(); e++) { + final UsbEndpoint endpoint = usbInterface.getEndpoint(e); + if (endpoint.getType() == UsbConstants.USB_ENDPOINT_XFER_BULK + && endpoint.getDirection() == UsbConstants.USB_DIR_IN) { + return endpoint; + } + } + return null; + } + + @Override + public String getSerial() { + try { + return _device.getSerialNumber(); + } catch (SecurityException e) { + return null; + } + } + + @Override + public void setReadQueue(final int bufferCount, final int bufferSize) { + if (bufferCount < 0 || bufferSize < 0) { + throw new IllegalArgumentException("setReadQueue: negative arguments"); + } + // D2XX manages its own read buffering; these values are stored for reflection only. + _readQueueBufferCount = bufferCount; + _readQueueBufferSize = bufferSize; + } + + @Override + public int getReadQueueBufferCount() { + return _readQueueBufferCount; + } + + @Override + public int getReadQueueBufferSize() { + return _readQueueBufferSize; + } + + @FunctionalInterface + private interface D2xxOp { T run() throws IOException; } + + private T d2xxOp(final String desc, final D2xxOp op) throws IOException { + try { return op.run(); } + catch (final IOException e) { throw e; } + catch (final Throwable t) { + QGCLogger.e(TAG, "Error " + desc, t); + throw new IOException(desc + " failed: " + t.getMessage(), t); + } + } + + @Override + public void open(final UsbDeviceConnection connection) throws IOException { + if (isOpen()) { + throw new IOException("Already open"); + } + if (connection == null) { + throw new IOException("Null USB device connection"); + } + // Snapshot the (manager, context) pair atomically so cleanup() on another + // thread cannot null one of them between this check and the openByUsbDevice + // call below. + final D2xxHandle handle = sD2xx.get(); + if (handle == null || !isFtdiDevice(_device)) { + throw new IOException("D2XX manager unavailable or device is not an FTDI device"); + } + + FT_Device d2xxDevice; + try { + d2xxDevice = handle.manager.openByUsbDevice(handle.appContext, _device); + } catch (Throwable t) { + throw new IOException("Failed to open D2XX FTDI device " + _device.getDeviceName() + ": " + t.getMessage()); + } + + if (d2xxDevice == null || !d2xxDevice.isOpen()) { + throw new IOException("Failed to open D2XX FTDI device " + _device.getDeviceName()); + } + + _connection = connection; + _ftDevice = d2xxDevice; + + // FTDI default latency timer is 16ms, which caps short-read flush rate at ~62 Hz — + // bad for MAVLink telemetry. 1ms is the minimum the chip accepts. Best-effort. + try { + _ftDevice.setLatencyTimer((byte) 1); + } catch (Throwable t) { + QGCLogger.w(TAG, "setLatencyTimer failed: " + t.getMessage()); + } + } + + @Override + public void close() throws IOException { + if (_ftDevice != null) { + try { + _ftDevice.close(); + } catch (Throwable t) { + QGCLogger.w(TAG, "Error closing D2XX device: " + t.getMessage()); + } + _ftDevice = null; + } + + if (_connection != null) { + _connection.close(); + _connection = null; + } + } + + @Override + public int read(final byte[] dest, final int timeout) throws IOException { + return read(dest, dest.length, timeout); + } + + @Override + public int read(final byte[] dest, final int length, final int timeout) throws IOException { + ensureOpen(); + if (dest == null) { + throw new IOException("Null read buffer"); + } + if (length <= 0) { + return 0; + } + + final int readLength = Math.min(length, dest.length); + try { + final int bytesRead = _ftDevice.read(dest, readLength, timeout); + return Math.max(0, Math.min(bytesRead, readLength)); + } catch (Throwable t) { + // Hot-unplug surfaces from D2XX as RuntimeException / NullPointerException + // out of JNI (the lib doesn't declare IOException). Returning 0 here + // would loop SerialInputOutputManager forever without firing onRunError, + // so the C++ side never sees EXC_RESOURCE and the port stays "open" from + // its perspective. Throw so the IO manager exits and the listener-mute + // / token-stale path runs. + QGCLogger.e(TAG, "Error reading D2XX data", t); + throw new IOException("D2XX read error: " + t.getMessage(), t); + } + } + + @Override + public void write(final byte[] src, final int timeout) throws IOException { + write(src, src.length, timeout); + } + + @Override + public void write(final byte[] src, final int length, final int timeout) throws IOException { + ensureOpen(); + if (src == null) { + throw new IOException("Null write buffer"); + } + if (length <= 0) { + return; + } + + final int writeLength = Math.min(length, src.length); + d2xxOp("writing D2XX data", () -> { + // wait=true is required: FT_Device reuses a single UsbRequest per device and + // wait=false returns before the URB completes, so the next write throws + // IllegalStateException("this request is currently queued"). The cost is that + // each write blocks the JNI write thread until the FTDI chip physically clocks + // bytes out — fine at high baud, slow at low baud. This is why FT232R/FT232H + // USB-TTL adapters wired to low-baud TELEM ports are routed through mik3y by + // QGCUsbSerialProber instead. + final int written = _ftDevice.write(src, writeLength, true, timeout); + if (written < writeLength) { + throw new IOException("D2XX write failed or short write: " + written + " / " + writeLength); + } + return null; + }); + } + + @Override + public void setParameters(final int baudRate, final int dataBits, final int stopBits, final int parity) throws IOException { + ensureOpen(); + d2xxOp("setting D2XX parameters", () -> { + final boolean baudOk = _ftDevice.setBaudRate(baudRate); + final boolean charsOk = _ftDevice.setDataCharacteristics( + toD2xxDataBits(dataBits), toD2xxStopBits(stopBits), toD2xxParity(parity)); + if (!baudOk || !charsOk) { + throw new IOException("Failed to set FTDI serial parameters"); + } + return null; + }); + _currentBaudRate = baudRate; + final java.util.function.IntConsumer l = _baudListener; + if (l != null) l.accept(baudRate); + } + + /** Current baud configured on the chip (last successful setParameters). */ + public int getCurrentBaudRate() { + return _currentBaudRate; + } + + /** Registers a listener invoked after every successful {@link #setParameters} call. + * Fires once immediately so a listener wired post-open picks up the current baud. */ + public void setBaudListener(final java.util.function.IntConsumer listener) { + _baudListener = listener; + if (listener != null) listener.accept(_currentBaudRate); + } + + /** Builds the write-op closure for an {@link AsyncUsbWritePump#forD2xx} worker. The + * pump's single worker calls this; we re-enter {@code d2xxOp} for thread-safe error + * translation. The returned op must only be called from one thread (D2XX is single-URB); + * the pump enforces that with workerCount=1. */ + public AsyncUsbWritePump.WriteOp asyncWriteOp() { + return (buf, len, timeoutMs) -> { + ensureOpen(); + final int writeLen = Math.min(len, buf.length); + return d2xxOp("writing D2XX data (async)", () -> { + final int n = _ftDevice.write(buf, writeLen, true, timeoutMs); + if (n < writeLen) { + throw new IOException("D2XX short write: " + n + "/" + writeLen); + } + return n; + }); + }; + } + + @Override + public boolean getCD() throws IOException { + ensureOpen(); + return readModemStatusBit(D2xxManager.FT_DCD); + } + + @Override + public boolean getCTS() throws IOException { + ensureOpen(); + return readModemStatusBit(D2xxManager.FT_CTS); + } + + @Override + public boolean getDSR() throws IOException { + ensureOpen(); + return readModemStatusBit(D2xxManager.FT_DSR); + } + + @Override + public boolean getDTR() throws IOException { + ensureOpen(); + return _dtr; + } + + @Override + public void setDTR(final boolean value) throws IOException { + ensureOpen(); + d2xxOp("setting D2XX control line DTR", () -> { + final boolean ok = value ? _ftDevice.setDtr() : _ftDevice.clrDtr(); + if (!ok) { + throw new IOException("Failed to set DTR"); + } + _dtr = value; + return null; + }); + } + + @Override + public boolean getRI() throws IOException { + ensureOpen(); + return readModemStatusBit(D2xxManager.FT_RI); + } + + @Override + public boolean getRTS() throws IOException { + ensureOpen(); + return _rts; + } + + @Override + public void setRTS(final boolean value) throws IOException { + ensureOpen(); + d2xxOp("setting D2XX control line RTS", () -> { + final boolean ok = value ? _ftDevice.setRts() : _ftDevice.clrRts(); + if (!ok) { + throw new IOException("Failed to set RTS"); + } + _rts = value; + return null; + }); + } + + @Override + public EnumSet getControlLines() throws IOException { + ensureOpen(); + // One control transfer reads all modem bits atomically, not four separate calls. + final int status = d2xxOp("reading D2XX modem status", _ftDevice::getModemStatus); + final EnumSet lines = EnumSet.noneOf(ControlLine.class); + if (_rts) lines.add(ControlLine.RTS); + if ((status & D2xxManager.FT_CTS) != 0) lines.add(ControlLine.CTS); + if (_dtr) lines.add(ControlLine.DTR); + if ((status & D2xxManager.FT_DSR) != 0) lines.add(ControlLine.DSR); + if ((status & D2xxManager.FT_DCD) != 0) lines.add(ControlLine.CD); + if ((status & D2xxManager.FT_RI) != 0) lines.add(ControlLine.RI); + return lines; + } + + @Override + public EnumSet getSupportedControlLines() { + return EnumSet.of(ControlLine.RTS, ControlLine.CTS, ControlLine.DTR, ControlLine.DSR, ControlLine.CD, ControlLine.RI); + } + + @Override + public void setFlowControl(final FlowControl flowControl) throws IOException { + ensureOpen(); + if (flowControl == FlowControl.XON_XOFF_INLINE) { + throw new IOException("XON/XOFF inline flow control is not supported by D2XX adapter"); + } + d2xxOp("setting D2XX flow control", () -> { + final byte XON = 0x11; // DC1 — standard ASCII XON + final byte XOFF = 0x13; // DC3 — standard ASCII XOFF + final short flowMode = toD2xxFlowControl(flowControl); + final boolean ok = _ftDevice.setFlowControl(flowMode, XON, XOFF); + if (!ok) { + throw new IOException("Failed to set flow control: " + flowControl); + } + _flowControl = flowControl; + return null; + }); + } + + @Override + public FlowControl getFlowControl() { + return isOpen() ? _flowControl : FlowControl.NONE; + } + + @Override + public EnumSet getSupportedFlowControl() { + return EnumSet.of(FlowControl.NONE, FlowControl.RTS_CTS, FlowControl.DTR_DSR, FlowControl.XON_XOFF); + } + + @Override + public boolean getXON() throws IOException { + ensureOpen(); + return false; + } + + @Override + public void purgeHwBuffers(final boolean purgeReadBuffers, final boolean purgeWriteBuffers) throws IOException { + ensureOpen(); + final byte purgeFlags = (byte) ( + (purgeReadBuffers ? D2xxManager.FT_PURGE_RX : 0) | + (purgeWriteBuffers ? D2xxManager.FT_PURGE_TX : 0)); + if (purgeFlags == 0) { + return; + } + d2xxOp("purging D2XX buffers", () -> { + if (!_ftDevice.purge(purgeFlags)) { + throw new IOException("Failed to purge FTDI buffers"); + } + return null; + }); + } + + @Override + public void setBreak(final boolean value) throws IOException { + ensureOpen(); + d2xxOp("setting D2XX break condition", () -> { + final boolean ok = value ? _ftDevice.setBreakOn() : _ftDevice.setBreakOff(); + if (!ok) { + throw new IOException("Failed to set break condition"); + } + return null; + }); + } + + @Override + public boolean isOpen() { + return _ftDevice != null && _ftDevice.isOpen(); + } + + private void ensureOpen() throws IOException { + if (!isOpen()) { + throw new IOException("Port not open"); + } + } + + private boolean readModemStatusBit(final int mask) throws IOException { + return (d2xxOp("reading D2XX modem status", _ftDevice::getModemStatus) & mask) != 0; + } + + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/QGCSerialListener.java b/android/src/org/mavlink/qgroundcontrol/serial/QGCSerialListener.java new file mode 100644 index 000000000000..327398952a3f --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/QGCSerialListener.java @@ -0,0 +1,82 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.mavlink.qgroundcontrol.serial.SerialConstants.EXC_RESOURCE; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.EXC_UNKNOWN; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.MAX_NATIVE_CALLBACK_DATA_BYTES; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import com.hoho.android.usbserial.util.SerialInputOutputManager; + +import java.io.IOException; + +/** + * Dispatches serial data callbacks from the IO manager thread to native code. + * + *

{@link #closed} is set by {@link UsbSerialLifecycle#stopIoManager} before + * {@code ioManager.stop()}. Both callbacks short-circuit when closed: the IO thread + * can deliver one final batch between {@code stop()} being signalled and the thread + * actually exiting, and we must not emit those events after the C++ side has begun + * teardown.

+ */ +final class QGCSerialListener implements SerialInputOutputManager.Listener { + + private static final String TAG = QGCSerialListener.class.getSimpleName(); + + private final long nativeToken; + private final UsbSerialLifecycle.Listener emitter; + // BENCHMARK INSTRUMENTATION (debug-only). Remove with the .record() call + // site below and the RateMonitor.java class to fully strip. + private final RateMonitor readMonitor = new RateMonitor(TAG, "onNewData"); + private volatile boolean closed = false; + + QGCSerialListener(final long nativeToken, final UsbSerialLifecycle.Listener emitter) { + this.nativeToken = nativeToken; + this.emitter = emitter; + } + + void mute() { + closed = true; + } + + @Override + public void onRunError(final Exception e) { + if (closed) return; + // IOException at runtime is the hot-unplug / device-lost path — expected, log as Warning. + // Everything else (RuntimeException, IllegalStateException, etc.) stays as Error. + final boolean isUnplug = (e instanceof IOException); + if (isUnplug) { + QGCLogger.w(TAG, "Runner stopped (device disconnected): " + e.getMessage()); + } else { + QGCLogger.e(TAG, "Runner stopped.", e); + } + final int kind = isUnplug ? EXC_RESOURCE : EXC_UNKNOWN; + emitter.emitException(nativeToken, kind, "Runner stopped: " + e.getMessage()); + } + + @Override + public void onNewData(final byte[] data) { + if (closed) return; + if (data == null || data.length == 0) { + QGCLogger.w(TAG, "Invalid data received"); + return; + } + + QGCLogger.v(TAG, () -> "onNewData n=" + data.length + + " first=0x" + String.format("%02x", data[0] & 0xff)); + readMonitor.record(data.length); + + if (data.length <= MAX_NATIVE_CALLBACK_DATA_BYTES) { + emitter.emitNewData(nativeToken, data, 0, data.length); + return; + } + + QGCLogger.w(TAG, "Large USB payload (" + data.length + " bytes), chunking before JNI callback"); + int offset = 0; + while (offset < data.length) { + final int chunkLen = Math.min(MAX_NATIVE_CALLBACK_DATA_BYTES, data.length - offset); + emitter.emitNewData(nativeToken, data, offset, chunkLen); + offset += chunkLen; + } + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbPermissionHandler.java b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbPermissionHandler.java new file mode 100644 index 000000000000..0d4aa8bbc8e1 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbPermissionHandler.java @@ -0,0 +1,258 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.app.PendingIntent; +import android.content.BroadcastReceiver; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbManager; +import androidx.core.content.ContextCompat; +import androidx.core.content.IntentCompat; + +import java.util.Map; +import java.util.concurrent.ConcurrentHashMap; +import java.util.concurrent.atomic.AtomicBoolean; +import java.util.concurrent.locks.ReentrantLock; + +/** + * Handles USB permission requests and USB attach/detach broadcasts on behalf of + * {@link QGCUsbSerialManager}. + * + *

Android has no {@code ActivityResultContract} for USB host permissions; the + * {@code UsbManager.requestPermission} API is inherently BroadcastReceiver-based + * through at least API 34. {@link ContextCompat#registerReceiver} handles the + * {@code RECEIVER_NOT_EXPORTED} flag without a hand-rolled SDK check.

+ */ +class QGCUsbPermissionHandler { + + private static final String TAG = QGCUsbPermissionHandler.class.getSimpleName(); + static final String ACTION_USB_PERMISSION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION"; + + /** Per-physical-device permission state. Owned here so callers don't need parallel sets. */ + enum PermissionStatus { PENDING, GRANTED, DENIED } + + /** + * Callback interface for USB device events. Implemented by + * {@link QGCUsbSerialManager}. + */ + interface Listener { + void onUsbDeviceAttached(UsbDevice device); + void onUsbDeviceDetached(UsbDevice device); + void onUsbPermissionGranted(UsbDevice device); + void onUsbPermissionDenied(UsbDevice device); + } + + private final Listener listener; + /** physicalDeviceId → status. Cleared per-device on detach so re-attach can re-prompt. */ + private final Map permissionStatus = new ConcurrentHashMap<>(); + + /** Guards {@link #usbPermissionIntent}, {@link #registered}, and {@link #appContext}. */ + private final ReentrantLock lock = new ReentrantLock(); + /** Fast-path idempotency check that avoids acquiring the lock for every call. */ + private final AtomicBoolean registered = new AtomicBoolean(false); + private PendingIntent usbPermissionIntent; + /** Captured at register() so unregister() always uses the same Application context. */ + private Context appContext; + /** Most recent device passed to {@link #requestPermission}; used as fallback when + * the OEM-broken ACTION_USB_PERMISSION arrives without EXTRA_DEVICE. */ + private volatile UsbDevice lastRequestedDevice; + /** Captured alongside {@link #lastRequestedDevice} for the same fallback path. */ + private volatile UsbManager lastUsbManager; + + private final BroadcastReceiver usbReceiver = new BroadcastReceiver() { + @Override + public void onReceive(final Context context, final Intent intent) { + final String action = intent.getAction(); + QGCLogger.i(TAG, "BroadcastReceiver USB action " + action); + if (action == null) { + return; + } + + switch (action) { + case ACTION_USB_PERMISSION: + handleUsbPermission(intent); + break; + case UsbManager.ACTION_USB_DEVICE_DETACHED: + handleUsbDeviceDetached(intent); + break; + case UsbManager.ACTION_USB_DEVICE_ATTACHED: + handleUsbDeviceAttached(intent); + break; + default: + break; + } + } + }; + + QGCUsbPermissionHandler(final Listener listener) { + this.listener = listener; + } + + /** + * Builds the {@link PendingIntent} and registers the receiver. + * Safe to call repeatedly — no-op if already registered. + */ + void register(final Context context) { + // Fast path: avoid lock acquisition when already registered. + if (registered.get()) { + return; + } + + lock.lock(); + try { + if (registered.get()) { + return; + } + + final Context ctx = context.getApplicationContext(); + final Intent permissionIntent = + new Intent(ACTION_USB_PERMISSION).setPackage(ctx.getPackageName()); + final int flags = PendingIntent.FLAG_UPDATE_CURRENT | PendingIntent.FLAG_IMMUTABLE; + usbPermissionIntent = PendingIntent.getBroadcast(ctx, 0, permissionIntent, flags); + + final IntentFilter filter = new IntentFilter(); + filter.addAction(UsbManager.ACTION_USB_DEVICE_ATTACHED); + filter.addAction(UsbManager.ACTION_USB_DEVICE_DETACHED); + filter.addAction(ACTION_USB_PERMISSION); + + try { + ContextCompat.registerReceiver( + ctx, + usbReceiver, + filter, + ContextCompat.RECEIVER_NOT_EXPORTED); + appContext = ctx; + registered.set(true); + QGCLogger.i(TAG, "BroadcastReceiver registered successfully."); + } catch (final Exception e) { + usbPermissionIntent = null; + QGCLogger.e(TAG, "Failed to register BroadcastReceiver", e); + } + } finally { + lock.unlock(); + } + } + + /** + * Unregisters the receiver and releases the {@link PendingIntent}. + * Safe to call when not registered. Uses the Application context captured + * during {@link #register} so it cannot mismatch the registration context. + */ + void unregister() { + if (!registered.get()) { + return; + } + + lock.lock(); + try { + if (!registered.get()) { + return; + } + try { + if (appContext != null) { + appContext.unregisterReceiver(usbReceiver); + QGCLogger.i(TAG, "BroadcastReceiver unregistered successfully."); + } + } catch (final IllegalArgumentException e) { + QGCLogger.w(TAG, "Receiver not registered: " + e.getMessage()); + } finally { + registered.set(false); + usbPermissionIntent = null; + appContext = null; + lastRequestedDevice = null; + lastUsbManager = null; + permissionStatus.clear(); + } + } finally { + lock.unlock(); + } + } + + /** + * Requests USB permission for {@code device}. Callers should check + * {@link UsbManager#hasPermission} before calling this. + */ + void requestPermission(final UsbManager usbManager, final UsbDevice device) { + final PendingIntent intent; + lock.lock(); + try { + intent = usbPermissionIntent; + } finally { + lock.unlock(); + } + if (intent == null) { + QGCLogger.e(TAG, "requestPermission called before register()"); + return; + } + lastRequestedDevice = device; + lastUsbManager = usbManager; + permissionStatus.put(device.getDeviceId(), PermissionStatus.PENDING); + usbManager.requestPermission(device, intent); + } + + /** Returns true if the user previously denied permission for {@code physicalDeviceId} + * this attach cycle. Cleared by {@link #clearDevice} on detach / re-grant. */ + boolean isDenied(final int physicalDeviceId) { + return permissionStatus.get(physicalDeviceId) == PermissionStatus.DENIED; + } + + /** Drops any cached permission state for {@code physicalDeviceId}; call on detach + * so the next physical re-attach can re-prompt the user. */ + void clearDevice(final int physicalDeviceId) { + permissionStatus.remove(physicalDeviceId); + } + + private void handleUsbPermission(final Intent intent) { + final boolean granted = intent.getBooleanExtra(UsbManager.EXTRA_PERMISSION_GRANTED, false); + UsbDevice device = getUsbDevice(intent); + boolean actuallyGranted = granted; + if (device == null) { + // Android-15 OEM quirk: ACTION_USB_PERMISSION delivered with no EXTRA_DEVICE and + // granted=false regardless of user choice. Fall back to the most recent request + // and the authoritative hasPermission() state. + final UsbDevice pending = lastRequestedDevice; + final UsbManager mgr = lastUsbManager; + if (pending == null || mgr == null) { + QGCLogger.w(TAG, "ACTION_USB_PERMISSION with no EXTRA_DEVICE and no pending request"); + return; + } + device = pending; + actuallyGranted = mgr.hasPermission(device); + QGCLogger.w(TAG, "ACTION_USB_PERMISSION malformed; resolved " + device.getDeviceName() + + " via hasPermission()=" + actuallyGranted); + } + if (device.equals(lastRequestedDevice)) { + lastRequestedDevice = null; + } + if (actuallyGranted) { + permissionStatus.put(device.getDeviceId(), PermissionStatus.GRANTED); + QGCLogger.i(TAG, "Permission granted to " + device.getDeviceName()); + listener.onUsbPermissionGranted(device); + } else { + permissionStatus.put(device.getDeviceId(), PermissionStatus.DENIED); + QGCLogger.i(TAG, "Permission denied for " + device.getDeviceName()); + listener.onUsbPermissionDenied(device); + } + } + + private void handleUsbDeviceDetached(final Intent intent) { + final UsbDevice device = getUsbDevice(intent); + if (device != null) { + listener.onUsbDeviceDetached(device); + } + } + + private void handleUsbDeviceAttached(final Intent intent) { + final UsbDevice device = getUsbDevice(intent); + if (device != null) { + listener.onUsbDeviceAttached(device); + } + } + + private static UsbDevice getUsbDevice(final Intent intent) { + return IntentCompat.getParcelableExtra(intent, UsbManager.EXTRA_DEVICE, UsbDevice.class); + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager.java b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager.java new file mode 100644 index 000000000000..10293247799a --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager.java @@ -0,0 +1,446 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.mavlink.qgroundcontrol.serial.SerialConstants.BAD_DEVICE_ID; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.MAX_NATIVE_CALLBACK_DATA_BYTES; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.content.Context; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbManager; +import android.os.SystemClock; +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialPort; +import com.hoho.android.usbserial.util.SerialInputOutputManager; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.concurrent.atomic.AtomicLong; +import java.util.function.Function; + +/** + * Java never holds a C++ pointer. {@code nativeToken} is an opaque random {@code long} + * that the C++ JniPointerRegistry maps to an {@code AndroidSerial*}; if the mapping is + * gone by the time Java calls back, the callback is a no-op. Token-based UAF protection, + * identical to Qt Bluetooth LowEnergyNotificationHub. + */ +public class QGCUsbSerialManager + implements QGCUsbPermissionHandler.Listener, UsbSerialLifecycle.Listener { + + private static final String TAG = QGCUsbSerialManager.class.getSimpleName(); + + private final NativeDataEmitter nativeDataEmitter = + new NativeDataEmitter(QGCUsbSerialManager::nativeDeviceNewData); + + private static final Object lifecycleLock = new Object(); + private static volatile QGCUsbSerialManager sInstance; + + /** + * Creates the singleton. No-op if already created. + * Should be called once from {@code QGCActivity.onCreate()}. + */ + public static void createInstance(final Context context) { + synchronized (lifecycleLock) { + if (sInstance != null) { + return; + } + sInstance = new QGCUsbSerialManager(context); + } + } + + /** Returns the singleton, or {@code null} if not yet created. */ + public static QGCUsbSerialManager getInstance() { + return sInstance; + } + + /** + * Tears down the singleton. + * Should be called from {@code QGCActivity.onDestroy()}. + */ + public static void destroyInstance() { + synchronized (lifecycleLock) { + if (sInstance == null) { + return; + } + sInstance._destroy(); + sInstance = null; + } + } + + private final UsbManager usbManager; + private final Context appContext; + private final QGCUsbPermissionHandler permissionHandler; + private volatile NativeCallbacks nativeCallbacks = new JniNativeCallbacks(); + + private final UsbSerialEnumerator enumerator; + private final UsbSerialIoBridge ioBridge; + private final UsbSerialLifecycle lifecycle; + private final UsbDeviceRegistry deviceRegistry = new UsbDeviceRegistry(); + + private QGCUsbSerialManager(final Context context) { + appContext = context.getApplicationContext(); + usbManager = (UsbManager) appContext.getSystemService(Context.USB_SERVICE); + permissionHandler = new QGCUsbPermissionHandler(this); + + if (usbManager == null) { + QGCLogger.e(TAG, "Failed to get UsbManager"); + enumerator = new UsbSerialEnumerator(null, this::removeAllResourcesForPhysicalDevice); + lifecycle = new UsbSerialLifecycle(null, deviceRegistry, enumerator, this); + ioBridge = buildIoBridge(); + return; + } + + QGCFtdiSerialDriver.initialize(appContext); + enumerator = new UsbSerialEnumerator( + QGCUsbSerialProber.getQGCUsbSerialProber(), + this::removeAllResourcesForPhysicalDevice); + lifecycle = new UsbSerialLifecycle(usbManager, deviceRegistry, enumerator, this); + ioBridge = buildIoBridge(); + + permissionHandler.register(appContext); + + enumerator.updateCurrentDrivers(usbManager); + for (final UsbDevice device : usbManager.getDeviceList().values()) { + requestPermissionIfTracked(device); + } + } + + private UsbSerialIoBridge buildIoBridge() { + return new UsbSerialIoBridge(new UsbSerialIoBridge.PortResolver() { + @Override + public UsbSerialPort openPortOrWarn(final int deviceId, final String operation) { + final UsbSerialPort port = lifecycle.findPortByDeviceId(deviceId); + if (port == null) { + // Debug: null is the normal detach→drain race (findPortByDeviceId already logged). + QGCLogger.d(TAG, "Attempted to " + operation + + " on a null port for device ID " + deviceId); + return null; + } + if (!port.isOpen()) { + QGCLogger.d(TAG, "Attempted to " + operation + + " on a closed port for device ID " + deviceId); + return null; + } + return port; + } + @Override + public SerialInputOutputManager ioManager(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = deviceRegistry.getByHandle(deviceId); + return (res != null) ? res.ioManager() : null; + } + @Override + public AsyncUsbWritePump writePump(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = deviceRegistry.getByHandle(deviceId); + return (res != null) ? res.writePump() : null; + } + }); + } + + private void _destroy() { + for (final UsbDeviceRegistry.UsbDeviceResources res : + new ArrayList<>(deviceRegistry.allResources())) { + lifecycle.close(res.handle()); + } + + permissionHandler.unregister(); + QGCFtdiSerialDriver.cleanup(); + enumerator.clear(); + deviceRegistry.clear(); + } + + /** Routes a JNI call to the live instance; returns fallback when not initialised. + * JNI binds by name and signature — do not rename or change arg types without updating AndroidSerial.cc. */ + private static T withInstance(final T fallback, final Function op) { + final QGCUsbSerialManager mgr = getInstance(); + if (mgr == null) { + QGCLogger.e(TAG, "Manager not initialized"); + return fallback; + } + return op.apply(mgr); + } + + public static int getDeviceHandle(final int deviceId) { + return withInstance(-1, m -> m._getDeviceHandle(deviceId)); + } + + /** Returns an empty array (never null) when the manager is not yet + * initialised, so callers need no null check. */ + public static UsbPortInfo[] availablePortsInfo() { + return withInstance(new UsbPortInfo[0], QGCUsbSerialManager::_availablePortsInfo); + } + + /** + * Opens the device and applies serial parameters, flow control, and DTR in a single + * JNI roundtrip. Returns the device ID on success, BAD_DEVICE_ID on any failure (after + * which the port is fully closed and unregistered — no need for the C++ side to clean up). + */ + public static int openWithConfig(final String deviceName, final SerialParameters params, + final int flowControl, final boolean assertDtr, final long nativeToken) { + return withInstance(BAD_DEVICE_ID, mgr -> { + final int deviceId = mgr.lifecycle.open(deviceName, nativeToken); + if (deviceId == BAD_DEVICE_ID) { + return BAD_DEVICE_ID; + } + if (!mgr.ioBridge.setParameters(deviceId, params.baudRate(), params.dataBits(), + params.stopBits(), params.parity()) + || !mgr.ioBridge.setFlowControl(deviceId, flowControl) + || (assertDtr && !mgr.ioBridge.setControlLine(deviceId, UsbSerialPort.ControlLine.DTR, true))) { + QGCLogger.e(TAG, "Failed to apply post-open config for " + deviceName + "; rolling back"); + mgr.lifecycle.close(deviceId); + return BAD_DEVICE_ID; + } + return deviceId; + }); + } + + public static boolean startIoManager(final int deviceId) { + return withInstance(false, m -> m.lifecycle.startIoManager(deviceId)); + } + + public static boolean stopIoManager(final int deviceId) { + return withInstance(false, m -> m.lifecycle.stopIoManager(deviceId)); + } + + public static boolean ioManagerRunning(final int deviceId) { + return withInstance(false, m -> m.lifecycle.ioManagerRunning(deviceId)); + } + + public static boolean close(final int deviceId) { + return withInstance(false, m -> m.lifecycle.close(deviceId)); + } + + // TEMP: write-rate counter. Logs writes-per-5s every 5s on Android.Serial. Remove once + // pooling decision is made (see qserialport_android.cpp design notes). + private static final AtomicLong sWriteCount = new AtomicLong(); + private static volatile long sWriteWindowStartMs = 0; + + private static void countWrite() { + sWriteCount.incrementAndGet(); + final long now = SystemClock.elapsedRealtime(); + final long windowStart = sWriteWindowStartMs; + if (now - windowStart >= 5000) { + // Best-effort: a single thread wins the CAS; others append into the next window. + if (sWriteWindowStartMs == windowStart) { + sWriteWindowStartMs = now; + final long n = sWriteCount.getAndSet(0); + QGCLogger.i(TAG, "writes/5s=" + n + " (≈" + (n / 5) + "/s, ≈" + (n * 2 / 5) + " java-allocs/s)"); + } + } + } + + /** + * Zero-copy entry point from JNI. The C++ caller wraps its own buffer with + * {@code NewDirectByteBuffer} — no {@code NewByteArray}/{@code SetByteArrayRegion} + * copy occurs on the C++ side. One copy remains here (direct ByteBuffer → Java + * heap byte[]) because usb-serial-for-android's upstream API takes byte[]; the + * C++-side NewByteArray + SetByteArrayRegion copy is eliminated. + */ + public static int writeDirect(final int deviceId, final ByteBuffer data, final int length, + final int timeoutMSec) { + countWrite(); + return withInstance(-1, m -> m.ioBridge.writeDirect(deviceId, data, length, timeoutMSec)); + } + + /** Async variant of {@link #writeDirect}. Same one-copy contract; byte[] is freshly allocated because the IO manager retains the reference. */ + public static int writeAsyncDirect(final int deviceId, final ByteBuffer data, final int length, + final int timeoutMSec) { + countWrite(); + return withInstance(-1, m -> m.ioBridge.writeAsyncDirect(deviceId, data, length, timeoutMSec)); + } + + /** Immutable value-object carrying the four serial-port configuration fields. */ + public record SerialParameters(int baudRate, int dataBits, int stopBits, int parity) {} + + public static boolean setSerialParameters(final int deviceId, final SerialParameters params) { + return withInstance(false, m -> m.ioBridge.setParameters(deviceId, + params.baudRate(), params.dataBits(), params.stopBits(), params.parity())); + } + + public static boolean setDataTerminalReady(final int deviceId, final boolean on) { + return withInstance(false, m -> m.ioBridge.setControlLine(deviceId, UsbSerialPort.ControlLine.DTR, on)); + } + + public static boolean setRequestToSend(final int deviceId, final boolean on) { + return withInstance(false, m -> m.ioBridge.setControlLine(deviceId, UsbSerialPort.ControlLine.RTS, on)); + } + + public static int[] getControlLines(final int deviceId) { + return withInstance(new int[]{}, m -> m.ioBridge.getControlLines(deviceId)); + } + + public static int getFlowControl(final int deviceId) { + return withInstance(0, m -> m.ioBridge.getFlowControl(deviceId)); + } + + public static boolean setFlowControl(final int deviceId, final int flowControl) { + return withInstance(false, m -> m.ioBridge.setFlowControl(deviceId, flowControl)); + } + + public static boolean setBreak(final int deviceId, final boolean on) { + return withInstance(false, m -> m.ioBridge.setBreak(deviceId, on)); + } + + public static boolean purgeBuffers(final int deviceId, final boolean input, final boolean output) { + return withInstance(false, m -> m.ioBridge.purgeBuffers(deviceId, input, output)); + } + + @Override + public void onUsbDeviceAttached(final UsbDevice device) { + onDeviceAvailable(device); + } + + @Override + public void onUsbDeviceDetached(final UsbDevice device) { + final int physicalDeviceId = device.getDeviceId(); + permissionHandler.clearDevice(physicalDeviceId); + final List resourceIds = deviceRegistry.handlesForPhysicalDevice(physicalDeviceId); + for (final Integer resourceId : resourceIds) { + final UsbDeviceRegistry.UsbDeviceResources res = deviceRegistry.getByHandle(resourceId); + if (res == null) { + continue; + } + final long nativeToken = res.nativeToken(); + lifecycle.close(resourceId); + emitDeviceHasDisconnected(nativeToken); + } + QGCLogger.i(TAG, "Device detached: " + device.getDeviceName()); + updateCurrentDrivers(); + } + + @Override + public void onUsbPermissionGranted(final UsbDevice device) { + onDeviceAvailable(device); + } + + @Override + public void onUsbPermissionDenied(final UsbDevice device) { + final int physicalDeviceId = device.getDeviceId(); + for (final Integer resourceId : deviceRegistry.handlesForPhysicalDevice(physicalDeviceId)) { + final UsbDeviceRegistry.UsbDeviceResources res = deviceRegistry.getByHandle(resourceId); + if (res != null) { + emitDeviceException(res.nativeToken(), SerialConstants.EXC_PERMISSION, + "USB Permission Denied"); + } + } + } + + interface NativeCallbacks { + void onDeviceHasDisconnected(long nativeToken); + void onDeviceException(long nativeToken, int kind, String message); + } + + private static final class JniNativeCallbacks implements NativeCallbacks { + @Override + public void onDeviceHasDisconnected(final long nativeToken) { + nativeDeviceHasDisconnected(nativeToken); + } + + @Override + public void onDeviceException(final long nativeToken, final int kind, final String message) { + nativeDeviceException(nativeToken, kind, message); + } + } + + // JNI bridge — bound by name from AndroidSerial.cc setNativeMethods(). + private static native void nativeDeviceHasDisconnected(final long nativeToken); + private static native void nativeDeviceException(final long nativeToken, final int kind, final String message); + /** + * JNI bridge — accepts a direct ByteBuffer so C++ can use GetDirectBufferAddress + * (zero-copy at the JNI boundary). {@code length} is the number of valid bytes + * in the buffer; capacity may be larger because the buffer comes from a pool. + * + *

Contract: the native side MUST consume {@code data} synchronously + * before returning. The buffer is recycled into the {@link NativeDataEmitter} + * pool as soon as this call returns; retaining the pointer past return is a + * use-after-free on off-heap memory. Bytes may be appended to a Java/owner-side + * queue inside the JNI call, but the {@link ByteBuffer} itself must not be stored.

+ */ + private static native void nativeDeviceNewData(final long nativeToken, final ByteBuffer data, final int length); + + @Override + public void emitException(final long nativeToken, final int kind, final String message) { + emitDeviceException(nativeToken, kind, message); + } + + @Override + public void emitNewData(final long nativeToken, final byte[] data, final int offset, final int length) { + emitDeviceNewData(nativeToken, data, offset, length); + } + + private void emitDeviceHasDisconnected(final long nativeToken) { + if (nativeToken != 0) { + nativeCallbacks.onDeviceHasDisconnected(nativeToken); + } + } + + private void emitDeviceException(final long nativeToken, final int kind, final String message) { + if (nativeToken != 0) { + nativeCallbacks.onDeviceException(nativeToken, kind, message); + } + } + + private void emitDeviceNewData(final long nativeToken, final byte[] data, final int offset, final int length) { + if (nativeToken == 0 || data == null || length <= 0) { + return; + } + // Payload exceeding this size bypassed QGCSerialListener's chunking and would overflow the pooled direct buffer. + if (length > MAX_NATIVE_CALLBACK_DATA_BYTES) { + throw new IllegalArgumentException("emitDeviceNewData length " + length + + " exceeds MAX_NATIVE_CALLBACK_DATA_BYTES " + MAX_NATIVE_CALLBACK_DATA_BYTES); + } + nativeDataEmitter.emit(nativeToken, data, offset, length); + } + + /** Central funnel for cold-start enumeration, USB-attach, and permission-granted callbacks. */ + private void onDeviceAvailable(final UsbDevice device) { + if (usbManager == null) { + QGCLogger.w(TAG, "USB serial manager not ready, ignoring device " + device.getDeviceName()); + return; + } + + enumerator.updateCurrentDrivers(usbManager); + requestPermissionIfTracked(device); + } + + /** Caller must have already refreshed the tracked-driver set via {@link UsbSerialEnumerator#updateCurrentDrivers}. */ + private void requestPermissionIfTracked(final UsbDevice device) { + if (enumerator.findDriverByDeviceId(device.getDeviceId()) == null) { + QGCLogger.d(TAG, "No driver found for device " + device.getDeviceName()); + return; + } + + if (usbManager.hasPermission(device)) { + return; + } + if (permissionHandler.isDenied(device.getDeviceId())) { + QGCLogger.d(TAG, "Skipping permission re-prompt for previously denied device " + + device.getDeviceName()); + return; + } + QGCLogger.i(TAG, "Requesting permission to use device " + device.getDeviceName()); + permissionHandler.requestPermission(usbManager, device); + } + + private void updateCurrentDrivers() { + enumerator.updateCurrentDrivers(usbManager); + } + + /** StaleDriverCallback target (method ref bound at constructor time, before {@code lifecycle} is assigned). */ + private void removeAllResourcesForPhysicalDevice(final int physicalDeviceId) { + lifecycle.removeAllResourcesForPhysicalDevice(physicalDeviceId); + } + + private int _getDeviceHandle(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = deviceRegistry.getByHandle(deviceId); + return (res != null) ? res.fileDescriptor() : -1; + } + + private UsbPortInfo[] _availablePortsInfo() { + if (usbManager == null) { + return new UsbPortInfo[0]; + } + return enumerator.availablePortsInfo(); + } + +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialProber.java b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialProber.java new file mode 100644 index 000000000000..dbf6ee1f78b0 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/QGCUsbSerialProber.java @@ -0,0 +1,49 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.hardware.usb.UsbDevice; +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialProber; + +/** + * Builds the {@link UsbSerialProber} used by {@link QGCUsbSerialManager}. + * + *

Driver matching is delegated to mik3y's default probe table — class-descriptor + * probing for CDC-ACM, plus the library's built-in VID/PID lists for CP210x / FTDI / + * CH34x / Prolific. The only QGC-specific behavior is preferring {@link QGCFtdiSerialDriver} + * (D2XX-backed) when D2XX actually enumerates the attached FTDI device. D2XX writes are + * routed through {@link AsyncUsbWritePump#forD2xx} (single worker, baud-throttled, + * {@code FT_Device.write(wait=true)}) so the chip's TX FIFO is never overrun. + */ +public class QGCUsbSerialProber { + + private static final String TAG = QGCUsbSerialProber.class.getSimpleName(); + + public static UsbSerialProber getQGCUsbSerialProber() { + return new UsbSerialProber(UsbSerialProber.getDefaultProbeTable()) { + @Override + public UsbSerialDriver probeDevice(final UsbDevice device) { + if (device == null) return null; + final String tag = String.format("vid=0x%04X pid=0x%04X (%s)", + device.getVendorId(), device.getProductId(), device.getDeviceName()); + // QGC issue #14146: canOpenViaD2XX returns true on Android 14/OneUI 6 + // when the subsequent D2XX open will actually fail. Gate the entire D2XX + // path off until hardware validation is done; VCP-mode FtdiSerialDriver + // covers the same chips with no functional gap for QGC's use case. + if (QGCFtdiSerialDriver.ENABLE_D2XX) { + final boolean d2xxAvail = QGCFtdiSerialDriver.isAvailable(); + final boolean isFtdi = QGCFtdiSerialDriver.isFtdiDevice(device); + if (d2xxAvail && isFtdi && QGCFtdiSerialDriver.canOpenViaD2XX(device)) { + QGCLogger.i(TAG, "probe " + tag + " -> QGCFtdiSerialDriver (D2XX)"); + return new QGCFtdiSerialDriver(device); + } + } + final UsbSerialDriver driver = super.probeDevice(device); + QGCLogger.i(TAG, "probe " + tag + + " -> " + (driver == null ? "no driver" : driver.getClass().getSimpleName())); + return driver; + } + }; + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/RateMonitor.java b/android/src/org/mavlink/qgroundcontrol/serial/RateMonitor.java new file mode 100644 index 000000000000..2695009eaf9d --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/RateMonitor.java @@ -0,0 +1,57 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import java.util.concurrent.atomic.AtomicLong; + +/** + * Lightweight rolling-window throughput counter used to benchmark JNI write/read + * crossings. Records call count + byte total per window and emits a single INFO + * log line every {@link #WINDOW_NS} nanoseconds. + * + *

Lock-free: callers contend only on two {@link AtomicLong}s on the fast path. + * The periodic flush is gated by a CAS on {@code windowStartNs} so exactly one + * thread snapshots the counters per window.

+ */ +final class RateMonitor { + + private static final long WINDOW_NS = 2_000_000_000L; + + private final String tag; + private final String label; + private final AtomicLong calls = new AtomicLong(); + private final AtomicLong bytes = new AtomicLong(); + private final AtomicLong maxLen = new AtomicLong(); + private final AtomicLong windowStartNs; + + RateMonitor(final String tag, final String label) { + this.tag = tag; + this.label = label; + this.windowStartNs = new AtomicLong(System.nanoTime()); + } + + void record(final int n) { + calls.incrementAndGet(); + bytes.addAndGet(n); + // Atomic max — only update if larger. + long prevMax; + do { + prevMax = maxLen.get(); + if (n <= prevMax) break; + } while (!maxLen.compareAndSet(prevMax, n)); + + final long now = System.nanoTime(); + final long start = windowStartNs.get(); + if (now - start < WINDOW_NS) return; + if (!windowStartNs.compareAndSet(start, now)) return; + + final long c = calls.getAndSet(0); + final long b = bytes.getAndSet(0); + final long mx = maxLen.getAndSet(0); + if (c == 0) return; + final double secs = (now - start) / 1e9; + QGCLogger.i(tag, String.format( + "bench %s calls=%d bytes=%d avg=%.1f max=%d rate=%.1f/s bps=%.0f window=%.2fs", + label, c, b, (double) b / c, mx, c / secs, b / secs, secs)); + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/SerialConstants.java b/android/src/org/mavlink/qgroundcontrol/serial/SerialConstants.java new file mode 100644 index 000000000000..9076db2b0a87 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/SerialConstants.java @@ -0,0 +1,41 @@ +package org.mavlink.qgroundcontrol.serial; + +/** Constants shared across the serial subsystem — values that must agree with the JNI chunking contract. */ +final class SerialConstants { + + private SerialConstants() {} + + /** Sentinel device-id returned on any open/setup failure. */ + static final int BAD_DEVICE_ID = 0; + + /** Default read buffer size handed to {@code SerialInputOutputManager}. */ + static final int READ_BUF_SIZE = 2048; + + // SerialInputOutputManager queue depth. usb-serial-for-android 3.10.0 release notes: + // queuing multiple buffers prevents data loss when the JVM stalls (GC / JIT) between + // kernel USB copies during permanent read() with timeout=0 at >115200 baud. 3 buffers + // covers typical Android GC pauses (<30ms each) at MAVLink rates without growing + // worst-case latency past one buffer-fill period. + static final int READ_QUEUE_DEPTH = 3; + + /** Per-callback chunk size — Lifecycle must chunk to this; Manager guards. */ + static final int MAX_NATIVE_CALLBACK_DATA_BYTES = 16 * 1024; + + /** Direct ByteBuffer pool capacity — one buffer per open port's read thread is typical. */ + static final int DIRECT_BUFFER_POOL_CAP = 8; + + // Exception-kind ordinals delivered through nativeDeviceException. Must match + // AndroidSerial::JavaExceptionKind in src/Android/AndroidSerial.h. + static final int EXC_UNKNOWN = 0; + static final int EXC_RESOURCE = 1; // IOException at runtime — hot-unplug + static final int EXC_PERMISSION = 2; // USB permission denied + static final int EXC_OPEN_FAILED = 3; // Open-path failure (driver / port / connection) + + // FTDI vendor control-transfer constants (AN232B-04). Used by VCP-mode FTDI in + // UsbSerialLifecycle.openDriver to drop the chip latency timer from the 16ms + // default; D2XX path goes through QGCFtdiSerialPort which uses FT_Device.setLatencyTimer. + static final int FTDI_REQTYPE_OUT = 0x40; // vendor | host-to-device | device + static final int FTDI_SIO_SET_LATENCY = 0x09; + static final int FTDI_LATENCY_MS = 1; // 1ms minimum; default is 16ms + static final int FTDI_CTRL_TIMEOUT_MS = 100; +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/UsbDeviceRegistry.java b/android/src/org/mavlink/qgroundcontrol/serial/UsbDeviceRegistry.java new file mode 100644 index 000000000000..329e19a05502 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/UsbDeviceRegistry.java @@ -0,0 +1,277 @@ +package org.mavlink.qgroundcontrol.serial; + +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.util.SerialInputOutputManager; +import android.hardware.usb.UsbDeviceConnection; + +import java.util.ArrayList; +import java.util.List; +import java.util.concurrent.ConcurrentHashMap; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; +import java.util.function.UnaryOperator; + +/** + * Maps JNI int handles to USB port resources. Single source of truth keyed by + * handle; (physicalDeviceId, portIndex) dedup is enforced by a synchronized + * register path. + * + *

Multi-field updates are atomic via {@link AtomicReference#updateAndGet} — + * a reader always observes a self-consistent {@link UsbDeviceResources} snapshot. + * + *

Token invariant: Java never holds a C++ pointer. {@code nativeToken} + * is an opaque counter that the C++ JniPointerRegistry maps to an + * {@code AndroidSerial*}; if the mapping is gone by the time Java calls back, + * the callback is a no-op. + */ +final class UsbDeviceRegistry { + + /** + * Per-handle lifecycle state. Transitions are linear: + * {@code REGISTERED → OPEN → IO_READY → CLOSING}. {@link UsbSerialLifecycle} + * owns transitions; callers query state instead of inferring it from + * field-presence checks. {@link SerialInputOutputManager#getState()} is still + * the authoritative IO running/stopped/stopping signal because the IO + * thread can transition on its own (e.g., on read error). + */ + enum PortLifecycleState { + /** Placeholder allocated; no driver, port, or connection yet. */ + REGISTERED, + /** Driver/port opened, UsbDeviceConnection (or D2XX-owned equivalent) live. */ + OPEN, + /** SerialInputOutputManager constructed; ready to start, may already be running. */ + IO_READY, + /** Teardown in progress; new operations should bail. */ + CLOSING, + } + + /** + * Immutable snapshot of all resources associated with a single open USB + * serial port. Field updates produce new records via {@code with*} + * copy-constructors and are applied atomically through the registry's + * {@link AtomicReference}. + */ + static record UsbDeviceResources( + int handle, + UsbSerialDriver driver, + SerialInputOutputManager ioManager, + QGCSerialListener listener, + UsbDeviceConnection connection, + AsyncUsbWritePump writePump, + int fileDescriptor, + long nativeToken, + int portIndex, + int physicalDeviceId, + PortLifecycleState state) { + + UsbDeviceResources withDriver(UsbSerialDriver v) { + return new UsbDeviceResources(handle, v, ioManager, listener, connection, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withIoManager(SerialInputOutputManager v) { + return new UsbDeviceResources(handle, driver, v, listener, connection, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withListener(QGCSerialListener v) { + return new UsbDeviceResources(handle, driver, ioManager, v, connection, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withConnection(UsbDeviceConnection v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, v, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withWritePump(AsyncUsbWritePump v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, v, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withFileDescriptor(int v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, writePump, + v, nativeToken, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withNativeToken(long v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, writePump, + fileDescriptor, v, portIndex, physicalDeviceId, state); + } + + UsbDeviceResources withPortIndex(int v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, writePump, + fileDescriptor, nativeToken, v, physicalDeviceId, state); + } + + UsbDeviceResources withPhysicalDeviceId(int v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, writePump, + fileDescriptor, nativeToken, portIndex, v, state); + } + + UsbDeviceResources withState(final PortLifecycleState v) { + return new UsbDeviceResources(handle, driver, ioManager, listener, connection, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, v); + } + + /** Sets the five open-state fields and transitions to {@link PortLifecycleState#OPEN} + * in one record copy, cheaper under {@link AtomicReference#updateAndGet} retry. */ + UsbDeviceResources withOpenState(final UsbSerialDriver d, final int pi, final long token, + final int fd, final UsbDeviceConnection c, final AsyncUsbWritePump pump) { + return new UsbDeviceResources(handle, d, ioManager, listener, c, pump, fd, token, pi, + physicalDeviceId, PortLifecycleState.OPEN); + } + + /** Sets the IO manager + listener and transitions to {@link PortLifecycleState#IO_READY}. */ + UsbDeviceResources withIoReady(final SerialInputOutputManager io, final QGCSerialListener l) { + return new UsbDeviceResources(handle, driver, io, l, connection, writePump, + fileDescriptor, nativeToken, portIndex, physicalDeviceId, PortLifecycleState.IO_READY); + } + + // handle=0 collides with BAD_DEVICE_ID — caller must pass the real handle. + static UsbDeviceResources placeholder(final int handle, final int physicalDeviceId, final int portIndex) { + return new UsbDeviceResources( + handle, null, null, null, null, null, 0, 0L, + portIndex, physicalDeviceId, PortLifecycleState.REGISTERED); + } + } + + /** Keyed by JNI handle. */ + private final ConcurrentHashMap> resources = + new ConcurrentHashMap<>(); + + private final AtomicInteger nextHandle = new AtomicInteger(1); + + /** Serializes register + remove against each other and against the slow-path + * dedup scan in {@link #getOrCreateHandle}. Read paths are lock-free. */ + private final Object registrationLock = new Object(); + + /** + * Returns the int handle for the given (physicalDeviceId, portIndex) pair. + * If no entry exists, allocates a placeholder with a fresh handle. Concurrent + * callers for the same pair converge to the same handle. + */ + int getOrCreateHandle(final int physicalDeviceId, final int portIndex) { + // Fast path — lock-free scan. + UsbDeviceResources existing = findByPortKey(physicalDeviceId, portIndex); + if (existing != null) { + return existing.handle(); + } + + synchronized (registrationLock) { + // Re-scan under lock; another thread may have registered concurrently. + existing = findByPortKey(physicalDeviceId, portIndex); + if (existing != null) { + return existing.handle(); + } + + final int handle = + nextHandle.getAndUpdate(v -> (v >= Integer.MAX_VALUE) ? 1 : v + 1); + final UsbDeviceResources res = UsbDeviceResources.placeholder(handle, physicalDeviceId, portIndex); + resources.put(handle, new AtomicReference<>(res)); + return handle; + } + } + + /** Looks up a resource snapshot by JNI int handle. */ + UsbDeviceResources getByHandle(final int handle) { + final AtomicReference ref = resources.get(handle); + return (ref != null) ? ref.get() : null; + } + + /** Looks up a resource snapshot by (physicalDeviceId, portIndex) pair. */ + UsbDeviceResources getByPortKey(final int physicalDeviceId, final int portIndex) { + return findByPortKey(physicalDeviceId, portIndex); + } + + private UsbDeviceResources findByPortKey(final int physicalDeviceId, final int portIndex) { + for (final AtomicReference ref : resources.values()) { + final UsbDeviceResources r = ref.get(); + if (r != null && r.physicalDeviceId() == physicalDeviceId && r.portIndex() == portIndex) { + return r; + } + } + return null; + } + + /** Returns all handles whose entry has {@code physicalDeviceId}. */ + List handlesForPhysicalDevice(final int physicalDeviceId) { + final List handles = new ArrayList<>(); + for (final AtomicReference ref : resources.values()) { + final UsbDeviceResources res = ref.get(); + if (res != null && res.physicalDeviceId() == physicalDeviceId) { + handles.add(res.handle()); + } + } + return handles; + } + + /** + * Atomically applies {@code updater} to the current snapshot for + * {@code handle}. Standard {@link AtomicReference#updateAndGet} retry on CAS + * contention. No-op if no entry exists for {@code handle}. + */ + void updateByHandle(final int handle, final UnaryOperator updater) { + final AtomicReference ref = resources.get(handle); + if (ref != null) { + ref.updateAndGet(updater); + } + } + + /** + * Atomically applies {@code updater} and returns the snapshot that was + * replaced — the only safe way to extract a resource (e.g. owned + * UsbDeviceConnection) for cleanup without racing another caller. + * Returns {@code null} if no entry exists for {@code handle}. + */ + UsbDeviceResources getAndUpdateByHandle(final int handle, + final UnaryOperator updater) { + final AtomicReference ref = resources.get(handle); + return (ref != null) ? ref.getAndUpdate(updater) : null; + } + + /** + * Atomically nulls the connection field and returns the previous UsbDeviceResources + * for the caller to close. Closing here would couple the registry to UsbDeviceConnection + * lifecycle; callers handle close + log. Returns null if no entry, or the entry holds no connection. + */ + UsbDeviceConnection extractConnection(final int handle) { + final UsbDeviceResources prev = getAndUpdateByHandle(handle, r -> r.withConnection(null)); + return (prev != null) ? prev.connection() : null; + } + + /** Atomically nulls the writePump field and returns the previous reference for caller cleanup. */ + AsyncUsbWritePump extractWritePump(final int handle) { + final UsbDeviceResources prev = getAndUpdateByHandle(handle, r -> r.withWritePump(null)); + return (prev != null) ? prev.writePump() : null; + } + + /** Removes the entry for {@code handle}. Returns the last snapshot, or null. */ + UsbDeviceResources remove(final int handle) { + synchronized (registrationLock) { + final AtomicReference ref = resources.remove(handle); + return (ref != null) ? ref.get() : null; + } + } + + /** Clears all entries and resets the handle counter. */ + void clear() { + synchronized (registrationLock) { + resources.clear(); + nextHandle.set(1); + } + } + + /** Returns a snapshot of all current resource entries. */ + List allResources() { + final List snapshot = new ArrayList<>(resources.size()); + for (final AtomicReference ref : resources.values()) { + final UsbDeviceResources r = ref.get(); + if (r != null) { + snapshot.add(r); + } + } + return snapshot; + } + +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/UsbPortInfo.java b/android/src/org/mavlink/qgroundcontrol/serial/UsbPortInfo.java new file mode 100644 index 000000000000..2400e51bd08c --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/UsbPortInfo.java @@ -0,0 +1,15 @@ +package org.mavlink.qgroundcontrol.serial; + +/** + * Structured device info record returned to C++ via JNI. Java records + * auto-generate component accessors with the field name (e.g. + * {@code deviceName()}, {@code productId()}) which JNI calls as + * ordinary instance methods. + */ +public record UsbPortInfo( + String deviceName, + String productName, + String manufacturerName, + String serialNumber, + int productId, + int vendorId) {} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialEnumerator.java b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialEnumerator.java new file mode 100644 index 000000000000..ced8a8a83ce9 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialEnumerator.java @@ -0,0 +1,315 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbManager; + +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialPort; +import com.hoho.android.usbserial.driver.UsbSerialProber; + +import java.util.ArrayList; +import java.util.List; +import java.util.Objects; +import java.util.concurrent.locks.ReentrantLock; + +/** + * Owns the tracked-driver list and all device-name / port-index parsing. Acts as the + * single source of truth for "which serial drivers are currently attached" — every + * code path that needs to look up a driver by name, by physical-device id, or by + * exposed port name routes through this class. + * + *

All driver-list mutations go through {@link #lock} so that compound operations + * (probe → removeStale → addNew) are atomic. The {@link StaleDriverCallback} is + * invoked outside the lock to prevent re-entrancy deadlocks from the manager.

+ * + *

Stale-driver cleanup is delegated back to the caller via {@link StaleDriverCallback} + * because removing a driver also has to release its resource-registry entries, and + * that registry lives on the manager.

+ */ +final class UsbSerialEnumerator { + + private static final String TAG = UsbSerialEnumerator.class.getSimpleName(); + static final String PORT_SUFFIX = "#p"; + + interface StaleDriverCallback { + void onPhysicalDeviceRemoved(int physicalDeviceId); + } + + private final UsbSerialProber prober; + private final StaleDriverCallback staleCallback; + private final List drivers = new ArrayList<>(); + private final ReentrantLock lock = new ReentrantLock(); + + UsbSerialEnumerator(final UsbSerialProber prober, final StaleDriverCallback staleCallback) { + this.prober = prober; + this.staleCallback = staleCallback; + } + + boolean isEmpty() { + lock.lock(); + try { + return drivers.isEmpty(); + } finally { + lock.unlock(); + } + } + + void clear() { + lock.lock(); + try { + drivers.clear(); + } finally { + lock.unlock(); + } + } + + UsbSerialDriver findDriverByDeviceId(final int deviceId) { + lock.lock(); + try { + for (final UsbSerialDriver driver : drivers) { + if (driver.getDevice().getDeviceId() == deviceId) { + return driver; + } + } + return null; + } finally { + lock.unlock(); + } + } + + UsbSerialDriver findDriverByDeviceName(final String deviceName) { + lock.lock(); + try { + for (final UsbSerialDriver driver : drivers) { + if (driver.getDevice().getDeviceName().equals(deviceName)) { + return driver; + } + } + return null; + } finally { + lock.unlock(); + } + } + + /** Returns the freshly-probed driver list without mutating the tracked set. */ + List probeAll(final UsbManager usbManager) { + if (prober == null || usbManager == null) { + return new ArrayList<>(); + } + return prober.findAllDrivers(usbManager); + } + + /** Adds {@code newDriver} unless its physical device is already tracked. */ + void addDriver(final UsbSerialDriver newDriver) { + final UsbDevice device = newDriver.getDevice(); + lock.lock(); + try { + for (final UsbSerialDriver d : drivers) { + if (d.getDevice().getDeviceId() == device.getDeviceId()) { + QGCLogger.d(TAG, "Driver already tracked for device ID " + device.getDeviceId()); + return; + } + } + drivers.add(newDriver); + } finally { + lock.unlock(); + } + QGCLogger.i(TAG, "Adding new driver for device ID " + device.getDeviceId() + ": " + + device.getDeviceName() + + String.format(" vid=0x%04x pid=0x%04x", device.getVendorId(), device.getProductId())); + } + + /** + * Removes drivers whose physical device is no longer present in {@code currentDrivers}, + * and notifies the {@link StaleDriverCallback} so the caller can release any registry + * entries tied to that physical device. The callback is invoked outside the lock. + */ + void removeStaleDrivers(final List currentDrivers) { + final List stalePhysicalIds; + lock.lock(); + try { + stalePhysicalIds = removeStaleDriversLocked(currentDrivers); + } finally { + lock.unlock(); + } + invokeStaleCallbacks(stalePhysicalIds); + } + + /** Caller must hold {@link #lock}. Returns the stale physical-device IDs to notify. */ + private List removeStaleDriversLocked(final List currentDrivers) { + final List stalePhysicalIds = new ArrayList<>(); + drivers.removeIf(existingDriver -> { + final int existingPhysicalDeviceId = existingDriver.getDevice().getDeviceId(); + final boolean found = currentDrivers.stream() + .anyMatch(d -> d.getDevice().getDeviceId() == existingPhysicalDeviceId); + if (!found) { + stalePhysicalIds.add(existingPhysicalDeviceId); + QGCLogger.i(TAG, "Removed stale driver for device ID " + existingPhysicalDeviceId); + return true; + } + return false; + }); + return stalePhysicalIds; + } + + private void invokeStaleCallbacks(final List stalePhysicalIds) { + for (final int physicalDeviceId : stalePhysicalIds) { + staleCallback.onPhysicalDeviceRemoved(physicalDeviceId); + } + } + + void addNewDrivers(final List currentDrivers) { + lock.lock(); + try { + addNewDriversLocked(currentDrivers); + } finally { + lock.unlock(); + } + } + + /** Caller must hold {@link #lock}. */ + private void addNewDriversLocked(final List currentDrivers) { + for (final UsbSerialDriver newDriver : currentDrivers) { + final int deviceId = newDriver.getDevice().getDeviceId(); + boolean alreadyTracked = false; + for (final UsbSerialDriver d : drivers) { + if (d.getDevice().getDeviceId() == deviceId) { + alreadyTracked = true; + break; + } + } + if (alreadyTracked) { + QGCLogger.d(TAG, "Driver already tracked for device ID " + deviceId); + continue; + } + drivers.add(newDriver); + final UsbDevice dev = newDriver.getDevice(); + QGCLogger.i(TAG, "Adding new driver for device ID " + deviceId + ": " + + dev.getDeviceName() + + String.format(" vid=0x%04x pid=0x%04x", dev.getVendorId(), dev.getProductId())); + } + } + + void updateCurrentDrivers(final UsbManager usbManager) { + if (prober == null || usbManager == null) { + QGCLogger.w(TAG, "USB serial enumerator not ready, skipping driver refresh"); + return; + } + final List currentDrivers = probeAll(usbManager); + // Single lock acquisition makes remove-stale + add-new atomic; callbacks outside lock to prevent re-entrancy. + final List stalePhysicalIds; + lock.lock(); + try { + stalePhysicalIds = removeStaleDriversLocked(currentDrivers); + if (!currentDrivers.isEmpty()) { + addNewDriversLocked(currentDrivers); + } + } finally { + lock.unlock(); + } + invokeStaleCallbacks(stalePhysicalIds); + } + + UsbPortInfo[] availablePortsInfo() { + // Snapshot under lock; UsbDevice introspection (productName, serialNumber) can throw + // SecurityException and must not run with the lock held. + final List snapshot; + lock.lock(); + try { + if (drivers.isEmpty()) { + return new UsbPortInfo[0]; + } + snapshot = new ArrayList<>(drivers); + } finally { + lock.unlock(); + } + + final List portInfoList = new ArrayList<>(); + for (final UsbSerialDriver driver : snapshot) { + try { + final List ports = driver.getPorts(); + if (ports == null || ports.isEmpty()) { + continue; + } + final UsbDevice device = driver.getDevice(); + final int portCount = ports.size(); + for (final UsbSerialPort port : ports) { + final int portIndex = port.getPortNumber(); + final String exposedDeviceName = buildPortDeviceName(device, portIndex, portCount); + final UsbPortInfo info = new UsbPortInfo( + exposedDeviceName, + Objects.toString(device.getProductName(), ""), + Objects.toString(device.getManufacturerName(), ""), + Objects.toString(device.getSerialNumber(), ""), + device.getProductId(), + device.getVendorId()); + portInfoList.add(info); + } + } catch (final SecurityException e) { + // Some integrated controllers (e.g. Siyi UNIRC7) expose a USB device for video + // output. Accessing device info without permission throws SecurityException; + // swallow it to avoid log spam. + } + } + return portInfoList.toArray(new UsbPortInfo[0]); + } + + static final class DevicePortSpec { + final String baseDeviceName; + final int portIndex; + + DevicePortSpec(final String baseDeviceName, final int portIndex) { + this.baseDeviceName = baseDeviceName; + this.portIndex = Math.max(0, portIndex); + } + } + + static DevicePortSpec parseDevicePortSpec(final String deviceName) { + if (deviceName == null || deviceName.isEmpty()) { + return new DevicePortSpec("", 0); + } + final int split = deviceName.lastIndexOf(PORT_SUFFIX); + if (split <= 0) { + return new DevicePortSpec(deviceName, 0); + } + final String baseName = deviceName.substring(0, split); + final String suffix = deviceName.substring(split + PORT_SUFFIX.length()); + try { + final int parsedIndex = Integer.parseInt(suffix); + return new DevicePortSpec(baseName, Math.max(0, parsedIndex)); + } catch (final NumberFormatException e) { + QGCLogger.w(TAG, "Invalid device port suffix in " + deviceName + ", defaulting to port 0"); + return new DevicePortSpec(deviceName, 0); + } + } + + static String buildPortDeviceName(final UsbDevice device, final int portIndex, final int portCount) { + final String baseName = device.getDeviceName(); + if (portCount <= 1 && portIndex == 0) { + return baseName; + } + return baseName + PORT_SUFFIX + portIndex; + } + + static UsbSerialPort getPortFromDriver(final UsbSerialDriver driver, final int portIndex) { + if (driver == null) { + return null; + } + final List ports = driver.getPorts(); + if (ports == null || ports.isEmpty()) { + return null; + } + for (final UsbSerialPort port : ports) { + if (port.getPortNumber() == portIndex) { + return port; + } + } + if (portIndex >= 0 && portIndex < ports.size()) { + return ports.get(portIndex); + } + return null; + } + +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialIoBridge.java b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialIoBridge.java new file mode 100644 index 000000000000..6917217e1e29 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialIoBridge.java @@ -0,0 +1,217 @@ +package org.mavlink.qgroundcontrol.serial; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import com.hoho.android.usbserial.driver.SerialTimeoutException; +import com.hoho.android.usbserial.driver.UsbSerialPort; +import com.hoho.android.usbserial.util.SerialInputOutputManager; + +import java.io.IOException; +import java.nio.ByteBuffer; + +/** + * Stateless wrapper around the per-port operations exposed via JNI: write, + * parameter / control-line / flow-control mutators, break, and buffer purge. + * + *

All instance methods take a {@code deviceId} and resolve it through the + * supplied {@link PortResolver}. This keeps the resource-registry plumbing out + * of this class — the bridge never sees the registry directly.

+ */ +final class UsbSerialIoBridge { + + private static final String TAG = UsbSerialIoBridge.class.getSimpleName(); + + /** Max single-write payload we expect (covers a MAVLink v2 max + headroom). */ + private static final int WRITE_SCRATCH_BYTES = 16384; + private static final int WRITE_SCRATCH_POOL_CAP = 4; + + /** Single-direction lookup the bridge needs to perform any operation. */ + interface PortResolver { + /** Returns the open port for {@code deviceId}, or null (after warning) if missing/closed. */ + UsbSerialPort openPortOrWarn(int deviceId, String operation); + /** Returns the IO manager for {@code deviceId}, or null if not registered. */ + SerialInputOutputManager ioManager(int deviceId); + /** Returns the async write pump for {@code deviceId}, or null if pump-less (FTDI VCP, init failure). */ + AsyncUsbWritePump writePump(int deviceId); + } + + @FunctionalInterface + private interface PortOp { + T run(UsbSerialPort port) throws IOException, UnsupportedOperationException; + } + + private final PortResolver resolver; + + // port.write/writeAsync take byte[], so the heap copy is unavoidable; the allocation is not. + private final BoundedPool writeScratchPool = new BoundedPool<>( + WRITE_SCRATCH_POOL_CAP, + length -> new byte[Math.max(WRITE_SCRATCH_BYTES, length)], + buf -> buf.length); + + // BENCHMARK INSTRUMENTATION (debug-only). Remove these fields, the + // RateMonitor.java class, and the .record() call sites to fully strip. + private final RateMonitor writeSyncMonitor = new RateMonitor(TAG, "writeDirect"); + private final RateMonitor writeAsyncMonitor = new RateMonitor(TAG, "writeAsyncDirect"); + + UsbSerialIoBridge(final PortResolver resolver) { + this.resolver = resolver; + } + + private T withOpenPort(final int deviceId, final String operation, final T fallback, + final PortOp op) { + final UsbSerialPort port = resolver.openPortOrWarn(deviceId, operation); + if (port == null) { + return fallback; + } + try { + return op.run(port); + } catch (final UnsupportedOperationException e) { + QGCLogger.w(TAG, "Error " + operation + ": " + e); + return fallback; + } catch (final IOException e) { + QGCLogger.e(TAG, "Error " + operation, e); + return fallback; + } + } + + // data.hasArray() is always false for direct ByteBuffers — must transfer into heap byte[]. + int writeDirect(final int deviceId, final ByteBuffer data, final int length, final int timeoutMSec) { + final byte[] heap = writeScratchPool.borrow(length); + data.position(0); + data.get(heap, 0, length); + QGCLogger.v(TAG, () -> "writeDirect deviceId=" + deviceId + " n=" + length + + " first=0x" + String.format("%02x", heap[0] & 0xff)); + writeSyncMonitor.record(length); + // Async pump path: pump takes ownership of `heap` until its worker finishes, + // then fires the release callback. Eliminates the pump's prior per-submit + // System.arraycopy into a queue-owned byte[] — the buffer is enqueued in-place. + // Falls through to mik3y blocking write when pump is null (FTDI VCP / init failure). + final AsyncUsbWritePump pump = resolver.writePump(deviceId); + if (pump != null) { + return pump.submit(heap, length, () -> writeScratchPool.release(heap)); + } + try { + return withOpenPort(deviceId, "write", -1, port -> { + try { + port.write(heap, length, timeoutMSec); + return length; + } catch (final SerialTimeoutException e) { + QGCLogger.e(TAG, "Write timeout occurred", e); + return -1; + } + }); + } finally { + writeScratchPool.release(heap); + } + } + + int writeAsyncDirect(final int deviceId, final ByteBuffer data, final int length, final int timeoutMSec) { + final SerialInputOutputManager io = resolver.ioManager(deviceId); + if (io == null) { + QGCLogger.w(TAG, "IO Manager not found for device ID " + deviceId); + return -1; + } + // writeAsync retains the byte[] reference; must not pool it. + final byte[] heap = new byte[length]; + data.position(0); + data.get(heap, 0, length); + QGCLogger.v(TAG, () -> "writeAsyncDirect deviceId=" + deviceId + " n=" + length + + " first=0x" + String.format("%02x", heap[0] & 0xff)); + writeAsyncMonitor.record(length); + io.setWriteTimeout(timeoutMSec); + io.writeAsync(heap); + return length; + } + + boolean setParameters(final int deviceId, final int baudRate, final int dataBits, + final int stopBits, final int parity) { + return withOpenPort(deviceId, "setting parameters", false, port -> { + port.setParameters(baudRate, dataBits, stopBits, parity); + return true; + }); + } + + boolean setControlLine(final int deviceId, final UsbSerialPort.ControlLine controlLine, final boolean on) { + return withOpenPort(deviceId, "set " + controlLine, false, port -> { + if (!isControlLineSupported(port, controlLine)) { + QGCLogger.e(TAG, "Setting " + controlLine + " Not Supported"); + return false; + } + switch (controlLine) { + case DTR: port.setDTR(on); break; + case RTS: port.setRTS(on); break; + default: + QGCLogger.w(TAG, "Setting " + controlLine + " is not supported via this method."); + return false; + } + return true; + }); + } + + private static boolean isControlLineSupported(final UsbSerialPort port, + final UsbSerialPort.ControlLine controlLine) { + try { + return port.getSupportedControlLines().contains(controlLine); + } catch (final IOException e) { + QGCLogger.e(TAG, "Error getting supported control lines", e); + return false; + } + } + + int[] getControlLines(final int deviceId) { + return withOpenPort(deviceId, "getting control lines", new int[]{}, port -> + port.getControlLines().stream() + .mapToInt(UsbSerialPort.ControlLine::ordinal) + .toArray()); + } + + int getFlowControl(final int deviceId) { + final UsbSerialPort port = resolver.openPortOrWarn(deviceId, "get flow control"); + if (port == null) { + return 0; + } + if (port.getSupportedFlowControl().isEmpty()) { + QGCLogger.e(TAG, "Flow Control Not Supported"); + return 0; + } + return port.getFlowControl().ordinal(); + } + + boolean setFlowControl(final int deviceId, final int flowControl) { + if (flowControl < 0 || flowControl >= UsbSerialPort.FlowControl.values().length) { + QGCLogger.w(TAG, "Invalid flow control ordinal " + flowControl); + return false; + } + final UsbSerialPort.FlowControl target = UsbSerialPort.FlowControl.values()[flowControl]; + return withOpenPort(deviceId, "setting Flow Control", false, port -> { + final var supported = port.getSupportedFlowControl(); + if (supported.isEmpty() || !supported.contains(target)) { + QGCLogger.e(TAG, "Flow Control " + target + " not supported on this port"); + return false; + } + if (port.getFlowControl() == target) { + return true; + } + port.setFlowControl(target); + return true; + }); + } + + boolean setBreak(final int deviceId, final boolean on) { + return withOpenPort(deviceId, "setting break condition", false, port -> { + port.setBreak(on); + return true; + }); + } + + boolean purgeBuffers(final int deviceId, final boolean input, final boolean output) { + return withOpenPort(deviceId, "purging buffers", false, port -> { + try { + port.purgeHwBuffers(input, output); + } catch (UnsupportedOperationException ignored) { + // CDC-ACM drivers (Orange Cube et al.) have no HW FIFO to purge — treat as no-op. + } + return true; + }); + } +} diff --git a/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialLifecycle.java b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialLifecycle.java new file mode 100644 index 000000000000..e9f9e727f4f2 --- /dev/null +++ b/android/src/org/mavlink/qgroundcontrol/serial/UsbSerialLifecycle.java @@ -0,0 +1,413 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.mavlink.qgroundcontrol.serial.SerialConstants.BAD_DEVICE_ID; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.EXC_OPEN_FAILED; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.EXC_RESOURCE; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.EXC_UNKNOWN; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.FTDI_CTRL_TIMEOUT_MS; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.FTDI_LATENCY_MS; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.FTDI_REQTYPE_OUT; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.FTDI_SIO_SET_LATENCY; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.MAX_NATIVE_CALLBACK_DATA_BYTES; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.READ_BUF_SIZE; +import static org.mavlink.qgroundcontrol.serial.SerialConstants.READ_QUEUE_DEPTH; + +import org.mavlink.qgroundcontrol.QGCLogger; + +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbManager; +import android.os.Process; + +import com.hoho.android.usbserial.driver.FtdiSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialDriver; +import com.hoho.android.usbserial.driver.UsbSerialPort; +import com.hoho.android.usbserial.util.SerialInputOutputManager; + +import java.io.IOException; + +/** + * Owns the per-port open/close flow and the SerialInputOutputManager start/stop + * lifecycle. State (UsbDeviceRegistry, UsbManager, enumerator) is injected by the + * facade; native-emission is funneled through {@link Listener} so this class + * never depends on JNI directly. + */ +final class UsbSerialLifecycle { + + private static final String TAG = UsbSerialLifecycle.class.getSimpleName(); + + /** FTDI ports open/close the {@link UsbDeviceConnection} themselves; the manager + * must not store a second reference. CDC and other upstream drivers do not. */ + private static boolean ftdiOwnsConnection(final UsbSerialDriver driver) { + return driver instanceof QGCFtdiSerialDriver; + } + + /** Outbound channel for native-side notifications. Implemented by the manager facade. */ + interface Listener { + void emitException(long nativeToken, int kind, String message); + void emitNewData(long nativeToken, byte[] data, int offset, int length); + } + + private final UsbManager usbManager; + private final UsbDeviceRegistry registry; + private final UsbSerialEnumerator enumerator; + private final Listener listener; + + UsbSerialLifecycle(final UsbManager usbManager, + final UsbDeviceRegistry registry, + final UsbSerialEnumerator enumerator, + final Listener listener) { + this.usbManager = usbManager; + this.registry = registry; + this.enumerator = enumerator; + this.listener = listener; + } + + /** Closes every port whose registry entry maps to {@code physicalDeviceId}. */ + void removeAllResourcesForPhysicalDevice(final int physicalDeviceId) { + for (final int handle : registry.handlesForPhysicalDevice(physicalDeviceId)) { + close(handle); + } + } + + /** Looks up the port for a registered handle, or null. Shared with IoBridge resolver. + * Logs at debug — null lookups are normal during the detach→close race when C++ has + * pending writes still draining as the registry entry is being removed. */ + UsbSerialPort findPortByDeviceId(final int deviceId) { + if (deviceId == BAD_DEVICE_ID) { + QGCLogger.w(TAG, "Finding port failed for invalid Device ID " + deviceId); + return null; + } + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null || res.driver() == null) { + QGCLogger.d(TAG, "No resources found for device ID " + deviceId); + return null; + } + final UsbSerialPort port = UsbSerialEnumerator.getPortFromDriver(res.driver(), res.portIndex()); + if (port == null) { + QGCLogger.d(TAG, "No port available on device ID " + deviceId + + " at port index " + res.portIndex()); + return null; + } + return port; + } + + int open(final String deviceName, final long nativeToken) { + final UsbSerialEnumerator.DevicePortSpec spec = UsbSerialEnumerator.parseDevicePortSpec(deviceName); + final UsbSerialDriver driver = enumerator.findDriverByDeviceName(spec.baseDeviceName); + if (driver == null) { + // Common during BL→app fw transitions: device path changes mid-reconnect. C++ side + // surfaces DeviceNotFoundError, so this is debug-only to avoid duplicate noise. + QGCLogger.d(TAG, "Attempt to open unknown device " + deviceName); + return BAD_DEVICE_ID; + } + + final UsbDevice device = driver.getDevice(); + final UsbSerialPort port = UsbSerialEnumerator.getPortFromDriver(driver, spec.portIndex); + if (port == null) { + QGCLogger.w(TAG, "No port " + spec.portIndex + " available on device " + deviceName); + return BAD_DEVICE_ID; + } + + final int physicalDeviceId = device.getDeviceId(); + final int resourceId = registry.getOrCreateHandle(physicalDeviceId, spec.portIndex); + + final UsbDeviceRegistry.UsbDeviceResources existing = registry.getByHandle(resourceId); + if (existing == null) { + QGCLogger.e(TAG, "Resource entry missing for resourceId " + resourceId); + return BAD_DEVICE_ID; + } + // Re-opening an entry already past REGISTERED means a previous open didn't roll back fully; + // treat as fatal rather than silently overwriting state. + if (existing.state() != UsbDeviceRegistry.PortLifecycleState.REGISTERED) { + QGCLogger.w(TAG, "Open requested on handle " + resourceId + " already in state " + + existing.state() + "; refusing to reopen"); + return BAD_DEVICE_ID; + } + // openDriver emits its own EXC_OPEN_FAILED on each failure; rollback does not re-emit. + if (!openDriver(port, device, resourceId, driver, spec.portIndex, nativeToken)) { + QGCLogger.e(TAG, "Failed to open driver for device " + deviceName); + return rollbackOpen(resourceId, null); + } + + if (!createIoManager(resourceId, port, nativeToken)) { + listener.emitException(nativeToken, EXC_OPEN_FAILED, + "Failed to start I/O for device: " + deviceName); + return rollbackOpen(resourceId, port); + } + + QGCLogger.d(TAG, "Port open successful: " + port.toString()); + return resourceId; + } + + /** Tears down a partial open and returns BAD_DEVICE_ID. {@code port} may be null + * when openDriver failed before the port was usable; closeAndClearConnection is + * always safe (no-op when no connection was stored, e.g. FTDI-owned). */ + private int rollbackOpen(final int handle, final UsbSerialPort port) { + if (port != null) { + try { + port.close(); + } catch (final IOException e) { + QGCLogger.e(TAG, "Error closing port during rollback", e); + } + } + closeAndClearConnection(handle); + registry.remove(handle); + return BAD_DEVICE_ID; + } + + private boolean openDriver(final UsbSerialPort port, final UsbDevice device, + final int deviceId, final UsbSerialDriver driver, final int portIndex, + final long nativeToken) { + if (port == null) { + QGCLogger.w(TAG, "Null UsbSerialPort for device " + device.getDeviceName()); + listener.emitException(nativeToken, EXC_OPEN_FAILED, + "No serial port available for device: " + device.getDeviceName()); + return false; + } + + if (port.isOpen()) { + QGCLogger.d(TAG, "Port already open for device ID " + deviceId); + return true; + } + + final UsbDeviceConnection connection = usbManager.openDevice(device); + if (connection == null) { + QGCLogger.w(TAG, "No Usb Device Connection"); + listener.emitException(nativeToken, EXC_OPEN_FAILED, + "No USB device connection for device: " + device.getDeviceName()); + return false; + } + + try { + port.open(connection); + } catch (final IOException ex) { + QGCLogger.e(TAG, "Error opening driver for device " + device.getDeviceName(), ex); + listener.emitException(nativeToken, EXC_OPEN_FAILED, + "Error opening driver: " + ex.getMessage()); + connection.close(); + return false; + } + + // VCP-mode FTDI: drop chip latency timer from default 16ms so short MAVLink + // reads aren't held by the chip's batching window. wIndex is the 1-based + // port number (1 for single-port chips; A=1/B=2 on FT2232H, etc.). D2XX + // path handles its own latency timer inside QGCFtdiSerialPort.open(). + if (driver instanceof FtdiSerialDriver) { + try { + connection.controlTransfer(FTDI_REQTYPE_OUT, FTDI_SIO_SET_LATENCY, + FTDI_LATENCY_MS, portIndex + 1, null, 0, FTDI_CTRL_TIMEOUT_MS); + } catch (final Throwable t) { + QGCLogger.w(TAG, "FTDI setLatencyTimer failed: " + t.getMessage()); + } + } + + // QGCFtdiSerialDriver takes ownership of the UsbDeviceConnection inside port.open() + // and closes it from port.close(); storing a second reference here causes a double-close. + final boolean ftdiOwnsConn = ftdiOwnsConnection(driver); + final UsbDeviceConnection storedConn = ftdiOwnsConn ? null : connection; + // Async write pump pipelines outbound bytes. Two construction paths: + // bulkTransfer: for kernel-claimed interfaces (CDC-ACM, CP210x, CH34x, mik3y FTDI). + // D2XX: for QGCFtdiSerialDriver — D2XX claims the FTDI interface exclusively on its + // own connection, so we route writes through FT_Device.write(wait=true) via a + // single-worker pump with baud-aware throttling. + AsyncUsbWritePump pump = null; + try { + if (port instanceof QGCFtdiSerialDriver.QGCFtdiSerialPort) { + final QGCFtdiSerialDriver.QGCFtdiSerialPort ftdiPort = + (QGCFtdiSerialDriver.QGCFtdiSerialPort) port; + pump = AsyncUsbWritePump.forD2xx(ftdiPort.asyncWriteOp()); + final AsyncUsbWritePump finalPump = pump; + ftdiPort.setBaudListener(finalPump::setBaudRate); + QGCLogger.d(TAG, "AsyncUsbWritePump started (D2XX baud-throttled) for device ID " + deviceId); + } else { + final UsbEndpoint writeEp = port.getWriteEndpoint(); + if (writeEp != null) { + pump = AsyncUsbWritePump.forBulkTransfer(connection, writeEp); + QGCLogger.d(TAG, "AsyncUsbWritePump started (bulkTransfer) for device ID " + deviceId); + } + } + } catch (final Throwable t) { + QGCLogger.w(TAG, "AsyncUsbWritePump init failed; falling back to blocking write: " + t.getMessage()); + pump = null; + } + final int fd = connection.getFileDescriptor(); + if (registry.getByHandle(deviceId) != null) { + final AsyncUsbWritePump finalPump = pump; + registry.updateByHandle(deviceId, r -> + r.withOpenState(driver, portIndex, nativeToken, fd, storedConn, finalPump)); + } else { + // getOrCreateHandle always registers; close to avoid leaking the connection if missed. + if (pump != null) pump.close(); + connection.close(); + } + + QGCLogger.d(TAG, "Port Driver open successful"); + return true; + } + + private void closeAndClearConnection(final int handle) { + // Pump owns UsbRequests bound to the connection; must close before the connection. + final AsyncUsbWritePump pump = registry.extractWritePump(handle); + if (pump != null) { + try { pump.close(); } + catch (final Throwable t) { QGCLogger.w(TAG, "Error closing AsyncUsbWritePump: " + t.getMessage()); } + } + final UsbDeviceConnection conn = registry.extractConnection(handle); + if (conn != null) { + try { conn.close(); } + catch (final Throwable t) { QGCLogger.w(TAG, "Error closing UsbDeviceConnection: " + t.getMessage()); } + } + } + + private boolean createIoManager(final int deviceId, final UsbSerialPort port, + final long nativeToken) { + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null) { + QGCLogger.w(TAG, "No resources found for device ID " + deviceId); + return false; + } + + if (res.ioManager() != null) { + QGCLogger.i(TAG, "IO Manager already exists for device ID " + deviceId); + return true; + } + + if (port == null) { + QGCLogger.w(TAG, "Cannot create USB serial IO manager with null port for device ID " + + deviceId); + return false; + } + + final QGCSerialListener serialListener = new QGCSerialListener(nativeToken, listener); + final SerialInputOutputManager ioManager = new SerialInputOutputManager(port, serialListener); + + int readBufferSize = READ_BUF_SIZE; + final UsbEndpoint readEndpoint = port.getReadEndpoint(); + if (readEndpoint != null) { + readBufferSize = Math.max(readEndpoint.getMaxPacketSize(), READ_BUF_SIZE); + } + ioManager.setReadBufferSize(readBufferSize); + + QGCLogger.d(TAG, "Read Buffer Size: " + ioManager.getReadBufferSize()); + QGCLogger.d(TAG, "Write Buffer Size: " + ioManager.getWriteBufferSize()); + + try { + ioManager.setReadTimeout(0); + ioManager.setReadQueue(READ_QUEUE_DEPTH); + ioManager.setWriteTimeout(0); + ioManager.setThreadPriority(Process.THREAD_PRIORITY_URGENT_AUDIO); + } catch (final IllegalStateException e) { + QGCLogger.e(TAG, "IO Manager configuration error:", e); + return false; + } + + registry.updateByHandle(deviceId, r -> r.withIoReady(ioManager, serialListener)); + QGCLogger.d(TAG, "Serial I/O Manager created for device ID " + deviceId); + return true; + } + + boolean startIoManager(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null || res.ioManager() == null) { + QGCLogger.w(TAG, "IO Manager not found for device ID " + deviceId); + return false; + } + + final SerialInputOutputManager.State ioState = res.ioManager().getState(); + if (ioState == SerialInputOutputManager.State.RUNNING) { + return true; + } + + try { + res.ioManager().start(); + QGCLogger.d(TAG, "Serial I/O Manager started for device ID " + deviceId); + return true; + } catch (final IllegalStateException e) { + QGCLogger.e(TAG, "IO Manager Start exception:", e); + return false; + } + } + + boolean stopIoManager(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null || res.ioManager() == null) { + return false; + } + + final SerialInputOutputManager.State ioState = res.ioManager().getState(); + if (ioState == SerialInputOutputManager.State.STOPPED + || ioState == SerialInputOutputManager.State.STOPPING) { + return true; + } + + // Mute before stop(): the IO thread can deliver one final batch between the signal + // and actual exit; those events must not reach C++ after teardown begins. + if (res.listener() != null) { + res.listener().mute(); + } + + res.ioManager().stop(); // fire-and-return; stale callbacks are harmless (listener muted, token no-ops) + QGCLogger.d(TAG, "Serial I/O Manager stop signalled for device ID " + deviceId); + return true; + } + + boolean ioManagerRunning(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null || res.ioManager() == null) { + return false; + } + return res.ioManager().getState() == SerialInputOutputManager.State.RUNNING; + } + + boolean close(final int deviceId) { + final UsbDeviceRegistry.UsbDeviceResources res = registry.getByHandle(deviceId); + if (res == null) { + QGCLogger.d(TAG, "Close requested for already cleaned device ID " + deviceId); + return true; + } + if (res.state() == UsbDeviceRegistry.PortLifecycleState.CLOSING) { + // Another thread is already tearing down — let it finish; this call is a no-op. + QGCLogger.d(TAG, "Close already in progress for device ID " + deviceId); + return true; + } + registry.updateByHandle(deviceId, r -> r.withState(UsbDeviceRegistry.PortLifecycleState.CLOSING)); + + // port.isOpen()==false does NOT mean IO thread has exited — always stop first. + stopIoManager(deviceId); + + // Pump cancels in-flight UsbRequests; must run before port.close() releases the interface. + final AsyncUsbWritePump pump = registry.extractWritePump(deviceId); + if (pump != null) { + try { pump.close(); } + catch (final Throwable t) { QGCLogger.w(TAG, "Error closing AsyncUsbWritePump: " + t.getMessage()); } + } + + final UsbSerialPort port = findPortByDeviceId(deviceId); + if (port == null || !port.isOpen()) { + if (port == null) { + QGCLogger.w(TAG, "Attempted to close a null port for device ID " + deviceId); + } else { + QGCLogger.d(TAG, "Close requested for already closed device ID " + deviceId); + } + closeAndClearConnection(deviceId); + registry.remove(deviceId); + return true; + } + + try { + port.close(); + QGCLogger.d(TAG, "Device " + deviceId + " closed successfully."); + return true; + } catch (final IOException ex) { + QGCLogger.e(TAG, "Error closing driver:", ex); + return false; + } finally { + // Release the fd before removing the registry entry; FTDI path stored null so this is a no-op there. + closeAndClearConnection(deviceId); + registry.remove(deviceId); + } + } + +} diff --git a/android/src/test/java/org/mavlink/qgroundcontrol/QGCUsbSerialManagerTest.java b/android/src/test/java/org/mavlink/qgroundcontrol/QGCUsbSerialManagerTest.java deleted file mode 100644 index e99de6b827fe..000000000000 --- a/android/src/test/java/org/mavlink/qgroundcontrol/QGCUsbSerialManagerTest.java +++ /dev/null @@ -1,60 +0,0 @@ -package org.mavlink.qgroundcontrol; - -import static org.junit.Assert.assertEquals; -import static org.junit.Assert.assertNotEquals; - -import org.junit.After; -import org.junit.Before; -import org.junit.Test; - -public class QGCUsbSerialManagerTest { - - @Before - public void setUp() { - QGCUsbSerialManager.resetResourceMappingsForTesting(); - } - - @After - public void tearDown() { - QGCUsbSerialManager.resetResourceMappingsForTesting(); - } - - @Test - public void parseDevicePortSpec_withoutSuffix_defaultsToPortZero() { - final String deviceName = "/dev/bus/usb/001/002"; - assertEquals(deviceName, QGCUsbSerialManager.getBaseDeviceNameForTesting(deviceName)); - assertEquals(0, QGCUsbSerialManager.getPortIndexForTesting(deviceName)); - } - - @Test - public void parseDevicePortSpec_withSuffix_extractsPortIndex() { - assertEquals("/dev/bus/usb/001/002", QGCUsbSerialManager.getBaseDeviceNameForTesting("/dev/bus/usb/001/002#p3")); - assertEquals(3, QGCUsbSerialManager.getPortIndexForTesting("/dev/bus/usb/001/002#p3")); - } - - @Test - public void parseDevicePortSpec_invalidSuffix_fallsBackToOriginalNameAndPortZero() { - final String malformed = "/dev/bus/usb/001/002#pabc"; - assertEquals(malformed, QGCUsbSerialManager.getBaseDeviceNameForTesting(malformed)); - assertEquals(0, QGCUsbSerialManager.getPortIndexForTesting(malformed)); - } - - @Test - public void resourceIdMapping_reusesSameAddressAndSeparatesPorts() { - final int first = QGCUsbSerialManager.getOrCreateResourceIdForTesting(42, 0); - final int second = QGCUsbSerialManager.getOrCreateResourceIdForTesting(42, 0); - final int otherPort = QGCUsbSerialManager.getOrCreateResourceIdForTesting(42, 1); - - assertEquals(first, second); - assertNotEquals(first, otherPort); - } - - @Test - public void resourceIdMapping_removedAddressGetsNewId() { - final int first = QGCUsbSerialManager.getOrCreateResourceIdForTesting(7, 2); - QGCUsbSerialManager.removeResourceMappingForTesting(first); - final int next = QGCUsbSerialManager.getOrCreateResourceIdForTesting(7, 2); - - assertNotEquals(first, next); - } -} diff --git a/android/src/test/java/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePumpTest.java b/android/src/test/java/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePumpTest.java new file mode 100644 index 000000000000..371fd5e6299d --- /dev/null +++ b/android/src/test/java/org/mavlink/qgroundcontrol/serial/AsyncUsbWritePumpTest.java @@ -0,0 +1,184 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertNotEquals; +import static org.junit.Assert.assertSame; +import static org.junit.Assert.assertTrue; + +import org.junit.After; +import org.junit.Test; + +import java.util.concurrent.CountDownLatch; +import java.util.concurrent.TimeUnit; +import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; + +public class AsyncUsbWritePumpTest { + + private AsyncUsbWritePump pump; + + @After + public void tearDown() { + if (pump != null) pump.close(); + } + + /** A WriteOp that records each invocation and counts bytes. */ + private static final class RecordingWriteOp implements AsyncUsbWritePump.WriteOp { + final AtomicInteger calls = new AtomicInteger(); + final AtomicInteger bytes = new AtomicInteger(); + final CountDownLatch firstCall = new CountDownLatch(1); + final AtomicReference lastBuf = new AtomicReference<>(); + @Override public int write(final byte[] buf, final int length, final int timeoutMs) { + calls.incrementAndGet(); + bytes.addAndGet(length); + lastBuf.set(buf); + firstCall.countDown(); + return length; + } + } + + /** Counts onComplete invocations + records the buffer to verify ownership returns. */ + private static final class ReleaseTracker implements Runnable { + final AtomicInteger calls = new AtomicInteger(); + @Override public void run() { calls.incrementAndGet(); } + } + + @Test + public void submit_reachesWorker_andFiresOnComplete() throws InterruptedException { + final RecordingWriteOp op = new RecordingWriteOp(); + pump = AsyncUsbWritePump.forD2xx(op); + final ReleaseTracker release = new ReleaseTracker(); + + final byte[] payload = new byte[64]; + final int rc = pump.submit(payload, payload.length, release); + + assertEquals(64, rc); + assertTrue("worker did not run", op.firstCall.await(2, TimeUnit.SECONDS)); + assertEquals(64, op.bytes.get()); + // Pump must enqueue the SAME buffer the caller handed in — no internal copy. + assertSame(payload, op.lastBuf.get()); + // Worker must fire the release callback after the write completes. + for (int i = 0; i < 50 && release.calls.get() == 0; i++) Thread.sleep(10); + assertEquals(1, release.calls.get()); + } + + @Test + public void submit_invalidLength_returnsMinusOne_andFiresOnComplete() { + pump = AsyncUsbWritePump.forD2xx(new RecordingWriteOp()); + final ReleaseTracker release = new ReleaseTracker(); + + assertEquals(-1, pump.submit(new byte[1], 0, release)); + assertEquals(-1, pump.submit(new byte[1], -5, release)); + assertEquals(-1, pump.submit(new byte[32 * 1024], 32 * 1024, release)); // > MAX_SUBMIT_BYTES + assertEquals(-1, pump.submit(null, 8, release)); + assertEquals(-1, pump.submit(new byte[4], 8, release)); // length > data.length + + // All five failure paths must release — otherwise callers leak pool buffers. + assertEquals(5, release.calls.get()); + } + + @Test + public void submit_afterClose_returnsMinusOne_andFiresOnComplete() { + pump = AsyncUsbWritePump.forD2xx(new RecordingWriteOp()); + pump.close(); + final ReleaseTracker release = new ReleaseTracker(); + + assertEquals(-1, pump.submit(new byte[8], 8, release)); + assertEquals(1, release.calls.get()); + } + + @Test + public void submit_throttle_starvation_returnsMinusOneOnDeadline() { + // Worker never returns from write — the queue fills and submit() eventually + // returns -1 via SUBMIT_TIMEOUT_MS without the test hanging. + // SUBMIT_TIMEOUT_MS is 2000ms; we cap at 3500ms to give scheduler slack. + final AsyncUsbWritePump.WriteOp blockingOp = (buf, len, t) -> { + try { Thread.sleep(60_000); } catch (final InterruptedException e) { Thread.currentThread().interrupt(); } + return len; + }; + pump = AsyncUsbWritePump.forD2xx(blockingOp); + final ReleaseTracker release = new ReleaseTracker(); + + // baud = 100 → 10 B/s refill → 16 KiB submit needs >100 min; deadline (2s) trips first. + pump.setBaudRate(100); + + final long start = System.nanoTime(); + final int rc = pump.submit(new byte[16 * 1024 - 1], 16 * 1024 - 1, release); + final long elapsedMs = (System.nanoTime() - start) / 1_000_000L; + + assertEquals(-1, rc); + assertEquals("throttle-timeout path must still fire onComplete", 1, release.calls.get()); + assertTrue("submit returned before 1500ms (elapsed=" + elapsedMs + ")", elapsedMs >= 1500); + assertTrue("submit hung past 3500ms (elapsed=" + elapsedMs + ")", elapsedMs <= 3500); + } + + @Test + public void close_unblocksThrottledSubmit_andFiresOnComplete() throws InterruptedException { + // Worker accepts writes instantly so the queue never blocks; the only path that + // can stall submit() is drainTokens(). close() must wake the bucketLock.wait(). + pump = AsyncUsbWritePump.forD2xx(new RecordingWriteOp()); + pump.setBaudRate(50); // 5 B/s — drainTokens for any reasonable payload will park + final ReleaseTracker release = new ReleaseTracker(); + + final CountDownLatch entered = new CountDownLatch(1); + final AtomicInteger result = new AtomicInteger(Integer.MIN_VALUE); + final Thread t = new Thread(() -> { + entered.countDown(); + result.set(pump.submit(new byte[4096], 4096, release)); + }, "submit-under-throttle"); + t.setDaemon(true); + t.start(); + + assertTrue(entered.await(1, TimeUnit.SECONDS)); + Thread.sleep(50); + pump.close(); + + t.join(2_000); + assertNotEquals("submit thread still stuck after close", Integer.MIN_VALUE, result.get()); + assertEquals(-1, result.get()); + assertEquals("close-unblock path must fire onComplete", 1, release.calls.get()); + } + + @Test + public void close_drainsQueuedTasks_andFiresAllOnComplete() throws InterruptedException { + // Worker blocks on its first call so subsequent submits queue up; close() must + // then drain the unprocessed queue and fire each task's onComplete. Without this + // drain step the caller's buffer pool slowly bleeds. + final CountDownLatch workerEntered = new CountDownLatch(1); + final CountDownLatch workerHold = new CountDownLatch(1); + final AsyncUsbWritePump.WriteOp blockingOp = (buf, len, t) -> { + workerEntered.countDown(); + try { workerHold.await(); } catch (final InterruptedException e) { Thread.currentThread().interrupt(); } + return len; + }; + pump = AsyncUsbWritePump.forD2xx(blockingOp); + final ReleaseTracker release = new ReleaseTracker(); + + // First submit enters the worker and blocks; subsequent queue up. + // D2XX_WORKER_THREADS = 1, queue capacity = workerCount = 1. + // So after the worker takes 1 task, the queue holds 1 more before submit blocks. + pump.submit(new byte[8], 8, release); + assertTrue(workerEntered.await(1, TimeUnit.SECONDS)); + pump.submit(new byte[8], 8, release); // queued, not yet processed + + // close() while one task is in-flight in the worker (its onComplete still fires + // via the worker's finally) and one is queued (must be drained-and-released). + workerHold.countDown(); // let the worker complete its current task before close interrupts + pump.close(); + + // Both submits → both onCompletes (one via worker finally, one via close drain). + assertEquals(2, release.calls.get()); + } + + @Test + public void setBaudRate_zero_disablesThrottle() throws InterruptedException { + final RecordingWriteOp op = new RecordingWriteOp(); + pump = AsyncUsbWritePump.forD2xx(op); + + pump.setBaudRate(100); + pump.setBaudRate(0); + final ReleaseTracker release = new ReleaseTracker(); + assertEquals(128, pump.submit(new byte[128], 128, release)); + assertTrue(op.firstCall.await(2, TimeUnit.SECONDS)); + } +} diff --git a/android/src/test/java/org/mavlink/qgroundcontrol/serial/BoundedPoolTest.java b/android/src/test/java/org/mavlink/qgroundcontrol/serial/BoundedPoolTest.java new file mode 100644 index 000000000000..501a0bae1e05 --- /dev/null +++ b/android/src/test/java/org/mavlink/qgroundcontrol/serial/BoundedPoolTest.java @@ -0,0 +1,75 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertNotSame; +import static org.junit.Assert.assertSame; + +import org.junit.Test; + +import java.util.concurrent.atomic.AtomicInteger; + +public class BoundedPoolTest { + + private static BoundedPool newIntArrayPool(final int capacity, final AtomicInteger allocs) { + return new BoundedPool<>( + capacity, + size -> { allocs.incrementAndGet(); return new int[size]; }, + arr -> arr.length); + } + + @Test + public void borrowFromEmptyPoolAllocates() { + final AtomicInteger allocs = new AtomicInteger(); + final BoundedPool pool = newIntArrayPool(2, allocs); + + final int[] item = pool.borrow(8); + + assertEquals(8, item.length); + assertEquals(1, allocs.get()); + } + + @Test + public void releasedItemIsReusedOnSubsequentBorrowOfSameOrSmallerSize() { + final AtomicInteger allocs = new AtomicInteger(); + final BoundedPool pool = newIntArrayPool(2, allocs); + + final int[] first = pool.borrow(16); + pool.release(first); + final int[] reused = pool.borrow(16); + final int[] smaller = pool.borrow(4); // empty again → must allocate + + assertSame(first, reused); + assertNotSame(first, smaller); + assertEquals(2, allocs.get()); + } + + @Test + public void undersizedPooledItemFallsThroughToAllocator() { + final AtomicInteger allocs = new AtomicInteger(); + final BoundedPool pool = newIntArrayPool(2, allocs); + + final int[] tiny = pool.borrow(4); + pool.release(tiny); + final int[] bigger = pool.borrow(64); + + assertNotSame(tiny, bigger); + assertEquals(64, bigger.length); + assertEquals(2, allocs.get()); + } + + @Test + public void releaseBeyondCapacityIsDroppedSilently() { + final AtomicInteger allocs = new AtomicInteger(); + final BoundedPool pool = newIntArrayPool(2, allocs); + + pool.release(new int[8]); + pool.release(new int[8]); + pool.release(new int[8]); // dropped — must not throw, must not exceed CAP + + // Drain the two retained items; the third borrow must hit the allocator. + pool.borrow(8); + pool.borrow(8); + pool.borrow(8); + assertEquals(1, allocs.get()); + } +} diff --git a/android/src/test/java/org/mavlink/qgroundcontrol/serial/SerialUnitTest.java b/android/src/test/java/org/mavlink/qgroundcontrol/serial/SerialUnitTest.java new file mode 100644 index 000000000000..c55bc218cd8c --- /dev/null +++ b/android/src/test/java/org/mavlink/qgroundcontrol/serial/SerialUnitTest.java @@ -0,0 +1,62 @@ +package org.mavlink.qgroundcontrol.serial; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertNotEquals; + +import org.junit.Before; +import org.junit.Test; + +public class SerialUnitTest { + + private UsbDeviceRegistry registry; + + @Before + public void setUp() { + registry = new UsbDeviceRegistry(); + } + + @Test + public void parseDevicePortSpec_withoutSuffix_defaultsToPortZero() { + final String deviceName = "/dev/bus/usb/001/002"; + final UsbSerialEnumerator.DevicePortSpec spec = + UsbSerialEnumerator.parseDevicePortSpec(deviceName); + assertEquals(deviceName, spec.baseDeviceName); + assertEquals(0, spec.portIndex); + } + + @Test + public void parseDevicePortSpec_withSuffix_extractsPortIndex() { + final UsbSerialEnumerator.DevicePortSpec spec = + UsbSerialEnumerator.parseDevicePortSpec("/dev/bus/usb/001/002#p3"); + assertEquals("/dev/bus/usb/001/002", spec.baseDeviceName); + assertEquals(3, spec.portIndex); + } + + @Test + public void parseDevicePortSpec_invalidSuffix_fallsBackToOriginalNameAndPortZero() { + final String malformed = "/dev/bus/usb/001/002#pabc"; + final UsbSerialEnumerator.DevicePortSpec spec = + UsbSerialEnumerator.parseDevicePortSpec(malformed); + assertEquals(malformed, spec.baseDeviceName); + assertEquals(0, spec.portIndex); + } + + @Test + public void resourceIdMapping_reusesSameAddressAndSeparatesPorts() { + final int first = registry.getOrCreateHandle(42, 0); + final int second = registry.getOrCreateHandle(42, 0); + final int otherPort = registry.getOrCreateHandle(42, 1); + + assertEquals(first, second); + assertNotEquals(first, otherPort); + } + + @Test + public void resourceIdMapping_removedAddressGetsNewId() { + final int first = registry.getOrCreateHandle(7, 2); + registry.remove(first); + final int next = registry.getOrCreateHandle(7, 2); + + assertNotEquals(first, next); + } +} diff --git a/src/Android/AndroidInit.cc b/src/Android/AndroidInit.cc index 44b56382b48e..15fef571bac2 100644 --- a/src/Android/AndroidInit.cc +++ b/src/Android/AndroidInit.cc @@ -1,4 +1,5 @@ #include "AndroidInterface.h" +#include "AndroidLogSink.h" #ifndef QGC_NO_SERIAL_LINK #include "AndroidSerial.h" #endif @@ -157,9 +158,10 @@ jint JNI_OnLoad(JavaVM* vm, void*) } AndroidInterface::setNativeMethods(); + AndroidLogSink::setNativeMethods(); #ifndef QGC_NO_SERIAL_LINK - AndroidSerial::setNativeMethods(); + AndroidSerial::initialize(); #endif QNativeInterface::QAndroidApplication::hideSplashScreen(333); @@ -182,8 +184,4 @@ void JNI_OnUnload(JavaVM* vm, void*) } _java_vm.store(nullptr, std::memory_order_release); - -#ifndef QGC_NO_SERIAL_LINK - AndroidSerial::cleanupJniCache(); -#endif } diff --git a/src/Android/AndroidInterface.cc b/src/Android/AndroidInterface.cc index c1c7bb02d683..f5a5dad25f7c 100644 --- a/src/Android/AndroidInterface.cc +++ b/src/Android/AndroidInterface.cc @@ -9,8 +9,10 @@ #include #include #include +#include #include #include +#include #include "AppSettings.h" #include "QGCApplication.h" @@ -20,20 +22,14 @@ QGC_LOGGING_CATEGORY(AndroidInterfaceLog, "Android.AndroidInterface") -namespace AndroidInterface { +Q_DECLARE_JNI_CLASS(QGCActivity, "org/mavlink/qgroundcontrol/QGCActivity") +namespace AndroidInterface { static std::function s_importCallback; +} // namespace AndroidInterface -static void jniLogDebug(JNIEnv*, jobject, jstring message) -{ - qCDebug(AndroidInterfaceLog) << QJniObject(message).toString(); -} - -static void jniLogWarning(JNIEnv*, jobject, jstring message) -{ - qCWarning(AndroidInterfaceLog) << QJniObject(message).toString(); -} - +// File-static (not in namespace) so Q_DECLARE_JNI_NATIVE_METHOD can name the function via +// QT_PREPEND_NAMESPACE. Mirrors Qt BLE jni_android.cpp. static void jniStoragePermissionsResult(JNIEnv*, jobject, jboolean granted) { if (!granted) { @@ -41,13 +37,17 @@ static void jniStoragePermissionsResult(JNIEnv*, jobject, jboolean granted) return; } - if (!qgcApp()) { + QPointer app = qgcApp(); + if (!app) { return; } (void)QMetaObject::invokeMethod( - qgcApp(), - []() { + app.data(), + [app]() { + if (!app) { + return; + } SettingsManager* const settingsManager = SettingsManager::instance(); if (!settingsManager) { return; @@ -72,7 +72,7 @@ static void jniStoragePermissionsResult(JNIEnv*, jobject, jboolean granted) return; } - const QString sdCardRootPath = getSDCardPath(); + const QString sdCardRootPath = AndroidInterface::getSDCardPath(); if (sdCardRootPath.isEmpty() || !QDir(sdCardRootPath).exists() || !QFileInfo(sdCardRootPath).isWritable()) { return; } @@ -85,6 +85,7 @@ static void jniStoragePermissionsResult(JNIEnv*, jobject, jboolean granted) }, Qt::QueuedConnection); } +Q_DECLARE_JNI_NATIVE_METHOD(jniStoragePermissionsResult, nativeStoragePermissionsResult) static void jniOnImportResult(JNIEnv* env, jobject, jstring filePathA) { @@ -92,25 +93,23 @@ static void jniOnImportResult(JNIEnv* env, jobject, jstring filePathA) const QString filePath = QString::fromUtf8(filePathCStr); env->ReleaseStringUTFChars(filePathA, filePathCStr); (void)QJniEnvironment::checkAndClearExceptions(env); - auto callback = std::move(s_importCallback); + auto callback = std::move(AndroidInterface::s_importCallback); if (!callback) { return; } callback(filePath); } +Q_DECLARE_JNI_NATIVE_METHOD(jniOnImportResult, onImportResult) + +namespace AndroidInterface { void setNativeMethods() { - qCDebug(AndroidInterfaceLog) << "Registering Native Functions"; - - const JNINativeMethod javaMethods[]{ - {"qgcLogDebug", "(Ljava/lang/String;)V", reinterpret_cast(jniLogDebug)}, - {"qgcLogWarning", "(Ljava/lang/String;)V", reinterpret_cast(jniLogWarning)}, - {"nativeStoragePermissionsResult", "(Z)V", reinterpret_cast(jniStoragePermissionsResult)}, - {"onImportResult", "(Ljava/lang/String;)V", reinterpret_cast(jniOnImportResult)}}; - QJniEnvironment env; - if (!env.registerNativeMethods(kJniQGCActivityClassName, javaMethods, std::size(javaMethods))) { + if (!env.registerNativeMethods({ + Q_JNI_NATIVE_METHOD(jniStoragePermissionsResult), + Q_JNI_NATIVE_METHOD(jniOnImportResult), + })) { qCWarning(AndroidInterfaceLog) << "Failed to register native methods for" << kJniQGCActivityClassName; } else { qCDebug(AndroidInterfaceLog) << "Native Functions Registered"; diff --git a/src/Android/AndroidLogSink.cc b/src/Android/AndroidLogSink.cc new file mode 100644 index 000000000000..bc3d30bf6e82 --- /dev/null +++ b/src/Android/AndroidLogSink.cc @@ -0,0 +1,73 @@ +#include +#include +#include +#include +#include + +#include + +#include "QGCLoggingCategory.h" + +// Log category that receives all Java-side log output forwarded through +// QGCNativeLogSink / QGCLogger. Enable with: +// QT_LOGGING_RULES="qgc.android.java=true" +QGC_LOGGING_CATEGORY(AndroidJavaLog, "qgc.android.java") + +Q_DECLARE_JNI_CLASS(QGCNativeLogSink, "org/mavlink/qgroundcontrol/QGCNativeLogSink") + +// Level ordinals must match QGCNativeLogSink.java constants. +namespace { +constexpr jint kLevelDebug = 0; +constexpr jint kLevelInfo = 1; +constexpr jint kLevelWarning = 2; +constexpr jint kLevelError = 3; +} // namespace + +// File-static (not anon-namespaced) so Q_DECLARE_JNI_NATIVE_METHOD can name it via +// QT_PREPEND_NAMESPACE. Matches the Qt BLE jni_android.cpp pattern. +static void nativeLog(JNIEnv* env, jobject /*obj*/, jint level, + jstring jTag, jstring jMessage) +{ + if (!jTag || !jMessage) { + return; + } + + const QString tag = QJniObject(jTag).toString(); + const QString message = QJniObject(jMessage).toString(); + (void)QJniEnvironment::checkAndClearExceptions(env); + + const QString formatted = tag + ": " + message; + + switch (level) { + case kLevelDebug: + qCDebug(AndroidJavaLog).noquote() << formatted; + break; + case kLevelInfo: + qCInfo(AndroidJavaLog).noquote() << formatted; + break; + case kLevelWarning: + qCWarning(AndroidJavaLog).noquote() << formatted; + break; + case kLevelError: + default: + qCCritical(AndroidJavaLog).noquote() << formatted; + break; + } +} +Q_DECLARE_JNI_NATIVE_METHOD(nativeLog) + +namespace AndroidLogSink { + +void setNativeMethods() +{ + QJniEnvironment env; + if (!env.registerNativeMethods({ + Q_JNI_NATIVE_METHOD(nativeLog), + })) { + qCWarning(AndroidJavaLog) << "Failed to register native methods for QGCNativeLogSink"; + } else { + qCDebug(AndroidJavaLog) << "QGCNativeLogSink native methods registered"; + } +} + +} // namespace AndroidLogSink diff --git a/src/Android/AndroidLogSink.h b/src/Android/AndroidLogSink.h new file mode 100644 index 000000000000..45caa9867b2b --- /dev/null +++ b/src/Android/AndroidLogSink.h @@ -0,0 +1,16 @@ +#pragma once + +#include + +Q_DECLARE_LOGGING_CATEGORY(AndroidJavaLog) + +namespace AndroidLogSink { + +/** + * Registers the JNI native method for QGCNativeLogSink.nativeLog(). + * Must be called from JNI_OnLoad (or equivalent) after the class loader + * is available. + */ +void setNativeMethods(); + +} // namespace AndroidLogSink diff --git a/src/Android/AndroidSerial.cc b/src/Android/AndroidSerial.cc index 70c0df9f3a02..857ed049dd38 100644 --- a/src/Android/AndroidSerial.cc +++ b/src/Android/AndroidSerial.cc @@ -1,975 +1,90 @@ #include "AndroidSerial.h" +#include "QGCSerialPortInfo.h" +#include "qandroidserialengine_p.h" -#include +#include #include #include -#include -#include -#include -#include -#include -#include -#include +#include -#include - -#include "AndroidInterface.h" #include "QGCLoggingCategory.h" -QGC_LOGGING_CATEGORY(AndroidSerialLog, "Android.AndroidSerial"); - -namespace AndroidSerial { - -// ---------------------------------------------------------------------------- -// Token-based pointer tracking (UAF protection) -// -// Java receives an opaque random jlong token instead of a raw C++ pointer. -// A bidirectional hash map under QReadWriteLock maps tokens ↔ pointers. -// JNI callbacks (readers) take a shared read lock; register/unregister -// (writers) take an exclusive write lock. Pattern follows Qt Bluetooth's -// LowEnergyNotificationHub. -// ---------------------------------------------------------------------------- - -static QReadWriteLock s_ptrLock; -static QHash s_tokenToPtr; -static QHash s_ptrToToken; - -void registerPointer(QSerialPortPrivate* ptr) -{ - if (!ptr) { - qCWarning(AndroidSerialLog) << "registerPointer called with null pointer"; - return; - } - - QWriteLocker locker(&s_ptrLock); - - const auto existingIt = s_ptrToToken.constFind(ptr); - if (existingIt != s_ptrToToken.cend()) { - s_tokenToPtr.remove(*existingIt); - s_ptrToToken.erase(existingIt); - } - - jlong token; - do { - token = static_cast(QRandomGenerator::global()->generate64()); - } while (token == 0 || s_tokenToPtr.contains(token)); - - s_tokenToPtr.insert(token, ptr); - s_ptrToToken.insert(ptr, token); -} - -void unregisterPointer(QSerialPortPrivate* ptr) -{ - if (!ptr) { - return; - } - - QWriteLocker locker(&s_ptrLock); - const jlong token = s_ptrToToken.take(ptr); - if (token == 0) { - return; - } - s_tokenToPtr.remove(token); -} - -static QSerialPortPrivate* lookupByToken(jlong token) -{ - QReadLocker locker(&s_ptrLock); - return s_tokenToPtr.value(token, nullptr); -} - -static jlong lookupToken(QSerialPortPrivate* ptr) -{ - QReadLocker locker(&s_ptrLock); - return s_ptrToToken.value(ptr, 0); -} +QGC_LOGGING_CATEGORY(AndroidSerialLog, "Android.Serial"); -static QSerialPort* lookupPortByTokenLocked(jlong token) -{ - QSerialPortPrivate* const serialPortPrivate = s_tokenToPtr.value(token, nullptr); - if (!serialPortPrivate) { - return nullptr; - } +Q_DECLARE_JNI_CLASS(QGCUsbSerialManager, "org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager") +Q_DECLARE_JNI_CLASS(UsbPortInfo, "org/mavlink/qgroundcontrol/serial/UsbPortInfo") - return qobject_cast(serialPortPrivate->q_ptr); -} +namespace AndroidSerial { -template -static bool dispatchToPortObject(QSerialPort* serialPort, Functor&& func, const char* context) +void initialize() { - if (!serialPort) { - qCWarning(AndroidSerialLog) << context << ": null serial port"; - return false; - } - - QThread* const targetThread = serialPort->thread(); - const bool sameThread = (targetThread == QThread::currentThread()); - const bool hasEventLoop = targetThread && targetThread->eventDispatcher(); - - if (sameThread) { - std::forward(func)(); - return true; - } - - if (hasEventLoop) { - // BlockingQueuedConnection ensures the operation completes on the target thread - // before returning to the JNI caller (e.g. device disconnect is fully processed - // before Java-side cleanup continues). - const bool ok = QMetaObject::invokeMethod(serialPort, std::forward(func), Qt::BlockingQueuedConnection); - if (!ok) { - qCWarning(AndroidSerialLog) << context << ": failed to invoke method on target thread"; - } - return ok; - } - - qCWarning(AndroidSerialLog) << context << ": target thread has no event loop, running inline fallback"; - std::forward(func)(); - return true; + QAndroidSerialEngine::initialize(); } -// ---------------------------------------------------------------------------- -// JNI method ID cache -// ---------------------------------------------------------------------------- +namespace { -struct JniMethodCache +// JNI deviceName arrives as "/dev/bus/usb//" (absolute) — strip /dev/ for +// portName like the upstream Qt path does, otherwise leave as-is. +QString portNameFromDevicePath(const QString &source) { - jmethodID availableDevicesInfo = nullptr; - jmethodID getDeviceId = nullptr; - jmethodID getDeviceHandle = nullptr; - jmethodID open = nullptr; - jmethodID close = nullptr; - jmethodID isDeviceNameOpen = nullptr; - jmethodID read = nullptr; - jmethodID write = nullptr; - jmethodID writeAsync = nullptr; - jmethodID setParameters = nullptr; - jmethodID getCarrierDetect = nullptr; - jmethodID getClearToSend = nullptr; - jmethodID getDataSetReady = nullptr; - jmethodID getDataTerminalReady = nullptr; - jmethodID setDataTerminalReady = nullptr; - jmethodID getRingIndicator = nullptr; - jmethodID getRequestToSend = nullptr; - jmethodID setRequestToSend = nullptr; - jmethodID getControlLines = nullptr; - jmethodID getFlowControl = nullptr; - jmethodID setFlowControl = nullptr; - jmethodID purgeBuffers = nullptr; - jmethodID setBreak = nullptr; - jmethodID startIoManager = nullptr; - jmethodID stopIoManager = nullptr; - jmethodID ioManagerRunning = nullptr; -}; - -static JniMethodCache s_methods; -static bool s_methodsCached = false; -static QMutex s_cacheLock; -static jclass s_serialManagerClass = nullptr; - -static bool cacheMethodIds(JNIEnv* env, jclass javaClass) -{ - struct MethodDef - { - jmethodID* target; - const char* name; - const char* sig; - }; - - const MethodDef defs[] = { - {&s_methods.availableDevicesInfo, "availableDevicesInfo", "()[Ljava/lang/String;"}, - {&s_methods.getDeviceId, "getDeviceId", "(Ljava/lang/String;)I"}, - {&s_methods.getDeviceHandle, "getDeviceHandle", "(I)I"}, - {&s_methods.open, "open", "(Ljava/lang/String;J)I"}, - {&s_methods.close, "close", "(I)Z"}, - {&s_methods.isDeviceNameOpen, "isDeviceNameOpen", "(Ljava/lang/String;)Z"}, - {&s_methods.read, "read", "(III)[B"}, - {&s_methods.write, "write", "(I[BII)I"}, - {&s_methods.writeAsync, "writeAsync", "(I[BI)I"}, - {&s_methods.setParameters, "setParameters", "(IIIII)Z"}, - {&s_methods.getCarrierDetect, "getCarrierDetect", "(I)Z"}, - {&s_methods.getClearToSend, "getClearToSend", "(I)Z"}, - {&s_methods.getDataSetReady, "getDataSetReady", "(I)Z"}, - {&s_methods.getDataTerminalReady, "getDataTerminalReady", "(I)Z"}, - {&s_methods.setDataTerminalReady, "setDataTerminalReady", "(IZ)Z"}, - {&s_methods.getRingIndicator, "getRingIndicator", "(I)Z"}, - {&s_methods.getRequestToSend, "getRequestToSend", "(I)Z"}, - {&s_methods.setRequestToSend, "setRequestToSend", "(IZ)Z"}, - {&s_methods.getControlLines, "getControlLines", "(I)[I"}, - {&s_methods.getFlowControl, "getFlowControl", "(I)I"}, - {&s_methods.setFlowControl, "setFlowControl", "(II)Z"}, - {&s_methods.purgeBuffers, "purgeBuffers", "(IZZ)Z"}, - {&s_methods.setBreak, "setBreak", "(IZ)Z"}, - {&s_methods.startIoManager, "startIoManager", "(I)Z"}, - {&s_methods.stopIoManager, "stopIoManager", "(I)Z"}, - {&s_methods.ioManagerRunning, "ioManagerRunning", "(I)Z"}, - }; - - for (const auto& def : defs) { - *def.target = env->GetStaticMethodID(javaClass, def.name, def.sig); - if (!*def.target) { - qCWarning(AndroidSerialLog) << "Failed to cache method:" << def.name << def.sig; - (void)QJniEnvironment::checkAndClearExceptions(env); - return false; - } - } - - s_methodsCached = true; - qCDebug(AndroidSerialLog) << "All JNI method IDs cached successfully"; - return true; + return source.startsWith(QLatin1String("/dev/")) ? source.mid(5) : source; } -// ---------------------------------------------------------------------------- -// Class resolution -// ---------------------------------------------------------------------------- +} // namespace -static jclass getSerialManagerClass() +QList availableDevices() { - QMutexLocker locker(&s_cacheLock); - - if (s_serialManagerClass && s_methodsCached) { - return s_serialManagerClass; - } - + QList serialPortInfoList; QJniEnvironment env; - if (!env.isValid()) { - qCWarning(AndroidSerialLog) << "Invalid QJniEnvironment"; - return nullptr; - } - if (!s_serialManagerClass) { - const jclass resolvedClass = env.findClass(kJniUsbSerialManagerClassName); - if (!resolvedClass) { - qCWarning(AndroidSerialLog) << "Class Not Found:" << kJniUsbSerialManagerClassName; - return nullptr; + const auto array = QJniObject::callStaticMethod>("availablePortsInfo"); + if (env.checkAndClearExceptions() || !array.isValid()) { + if (!array.isValid()) { + qCDebug(AndroidSerialLog) << "availablePortsInfo returned null/empty"; + } else { + qCWarning(AndroidSerialLog) << "Exception occurred while calling availablePortsInfo"; } - - s_serialManagerClass = static_cast(env->NewGlobalRef(resolvedClass)); - if (env->GetObjectRefType(resolvedClass) == JNILocalRefType) { - env->DeleteLocalRef(resolvedClass); - } - - if (!s_serialManagerClass) { - qCWarning(AndroidSerialLog) << "Failed to create global ref for class:" << kJniUsbSerialManagerClassName; - (void)env.checkAndClearExceptions(); - return nullptr; - } - } - - if (!s_methodsCached && !cacheMethodIds(env.jniEnv(), s_serialManagerClass)) { - qCWarning(AndroidSerialLog) << "Failed to cache JNI method IDs"; - env->DeleteGlobalRef(s_serialManagerClass); - s_serialManagerClass = nullptr; - s_methods = {}; - (void)env.checkAndClearExceptions(); - return nullptr; - } - - s_methodsCached = true; - (void)env.checkAndClearExceptions(); - return s_serialManagerClass; -} - -void cleanupJniCache() -{ - QMutexLocker locker(&s_cacheLock); - QJniEnvironment env; - if (s_serialManagerClass && env.isValid()) { - env->DeleteGlobalRef(s_serialManagerClass); - } - s_serialManagerClass = nullptr; - s_methods = {}; - s_methodsCached = false; -} - -// ---------------------------------------------------------------------------- -// Native method registration -// ---------------------------------------------------------------------------- - -// Forward declarations for JNI callbacks (defined below) -static void jniDeviceHasDisconnected(JNIEnv* env, jobject obj, jlong token); -static void jniDeviceNewData(JNIEnv* env, jobject obj, jlong token, jbyteArray data); -static void jniDeviceException(JNIEnv* env, jobject obj, jlong token, jstring message); - -void setNativeMethods() -{ - qCDebug(AndroidSerialLog) << "Registering Native Functions"; - - const JNINativeMethod javaMethods[]{ - {"nativeDeviceHasDisconnected", "(J)V", reinterpret_cast(jniDeviceHasDisconnected)}, - {"nativeDeviceNewData", "(J[B)V", reinterpret_cast(jniDeviceNewData)}, - {"nativeDeviceException", "(JLjava/lang/String;)V", reinterpret_cast(jniDeviceException)}, - }; - - QJniEnvironment env; - if (!env.registerNativeMethods(kJniUsbSerialManagerClassName, javaMethods, std::size(javaMethods))) { - qCWarning(AndroidSerialLog) << "Failed to register native methods for" << kJniUsbSerialManagerClassName; - return; - } - - if (!getSerialManagerClass()) { - qCWarning(AndroidSerialLog) << "Failed to cache JNI method IDs"; - return; - } - - qCDebug(AndroidSerialLog) << "Native Functions Registered Successfully"; -} - -// ---------------------------------------------------------------------------- -// JNI callbacks (called from Java threads) -// ---------------------------------------------------------------------------- - -static void jniDeviceHasDisconnected(JNIEnv*, jobject, jlong token) -{ - if (token == 0) { - qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected called with token=0"; - return; - } - - QPointer serialPort; - { - QReadLocker locker(&s_ptrLock); - serialPort = lookupPortByTokenLocked(token); - if (!serialPort) { - qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected: stale token, object already destroyed"; - return; - } - qCDebug(AndroidSerialLog) << "Device disconnected:" << serialPort->portName(); - } - - if (!dispatchToPortObject( - serialPort.data(), - [token]() { - QSerialPortPrivate* const p = lookupByToken(token); - if (!p) { - qCDebug(AndroidSerialLog) << "Token already invalidated in nativeDeviceHasDisconnected"; - return; - } - - QSerialPort* const port = qobject_cast(p->q_ptr); - if (port && port->isOpen()) { - port->close(); - qCDebug(AndroidSerialLog) << "Serial port closed in nativeDeviceHasDisconnected"; - } else { - qCDebug(AndroidSerialLog) << "Serial port was already closed in nativeDeviceHasDisconnected"; - } - }, - "nativeDeviceHasDisconnected")) { - qCWarning(AndroidSerialLog) << "nativeDeviceHasDisconnected: failed to dispatch cleanup"; - } -} - -static void jniDeviceNewData(JNIEnv* env, jobject, jlong token, jbyteArray data) -{ - constexpr jsize kMaxNativePayloadBytes = static_cast(MAX_READ_SIZE); - - if (token == 0) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData called with token=0"; - return; - } - - if (!data) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData called with null data"; - return; - } - - const jsize len = env->GetArrayLength(data); - if (len <= 0) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData received empty data array"; - return; - } - - const jsize cappedLen = (len > kMaxNativePayloadBytes) ? kMaxNativePayloadBytes : len; - if (cappedLen != len) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData payload exceeds limit, truncating from" << len << "to" - << cappedLen << "bytes"; - } - - QByteArray payload(cappedLen, Qt::Uninitialized); - env->GetByteArrayRegion(data, 0, cappedLen, reinterpret_cast(payload.data())); - if (QJniEnvironment::checkAndClearExceptions(env)) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData failed to copy JNI byte array"; - return; - } - - { - // Deliver inline while holding read lock so unregister/destroy cannot - // invalidate the pointer until this handoff is complete. - QReadLocker locker(&s_ptrLock); - QSerialPortPrivate* const serialPortPrivate = s_tokenToPtr.value(token, nullptr); - if (!serialPortPrivate) { - qCWarning(AndroidSerialLog) << "nativeDeviceNewData: stale token, object already destroyed"; - return; - } - - serialPortPrivate->newDataArrived(payload.constData(), payload.size()); - } -} - -static void jniDeviceException(JNIEnv*, jobject, jlong token, jstring message) -{ - if (token == 0) { - qCWarning(AndroidSerialLog) << "nativeDeviceException called with token=0"; - return; - } - - if (!message) { - qCWarning(AndroidSerialLog) << "nativeDeviceException called with null message"; - return; - } - - const QString exceptionMessage = QJniObject(message).toString(); - - QPointer serialPort; - { - QReadLocker locker(&s_ptrLock); - serialPort = lookupPortByTokenLocked(token); - if (!serialPort) { - qCWarning(AndroidSerialLog) << "nativeDeviceException: stale token, object already destroyed"; - return; - } - } - - qCWarning(AndroidSerialLog) << "Exception from Java:" << exceptionMessage; - - if (!dispatchToPortObject( - serialPort.data(), - [token, exceptionMessage]() { - QSerialPortPrivate* const p = lookupByToken(token); - if (!p) { - qCDebug(AndroidSerialLog) << "Token already invalidated in nativeDeviceException"; - return; - } - - p->exceptionArrived(exceptionMessage); - }, - "nativeDeviceException")) { - qCWarning(AndroidSerialLog) << "nativeDeviceException: failed to dispatch exception callback"; - } -} - -// ---------------------------------------------------------------------------- -// Helper: get env + class + check cached method in one shot -// ---------------------------------------------------------------------------- - -struct JniContext -{ - QJniEnvironment env; - jclass cls = nullptr; - bool valid = false; -}; - -static bool getContext(JniContext& ctx, const char* caller) -{ - if (!ctx.env.isValid()) { - qCWarning(AndroidSerialLog) << "Invalid QJniEnvironment in" << caller; - return false; - } - - ctx.cls = getSerialManagerClass(); - if (!ctx.cls) { - qCWarning(AndroidSerialLog) << "getSerialManagerClass returned null in" << caller; - return false; - } - - ctx.valid = true; - return true; -} - -// ---------------------------------------------------------------------------- -// Device enumeration -// ---------------------------------------------------------------------------- - -QList availableDevices() -{ - QList serialPortInfoList; - - JniContext ctx; - if (!getContext(ctx, "availableDevices")) - return serialPortInfoList; - - AndroidInterface::JniLocalRef objArray( - ctx.env.jniEnv(), - static_cast(ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.availableDevicesInfo))); - if (!objArray.get()) { - qCDebug(AndroidSerialLog) << "availableDevicesInfo returned null"; - (void)ctx.env.checkAndClearExceptions(); - return serialPortInfoList; - } - - if (ctx.env.checkAndClearExceptions()) { - qCWarning(AndroidSerialLog) << "Exception occurred while calling availableDevicesInfo"; return serialPortInfoList; } - const jsize count = ctx.env->GetArrayLength(objArray.get()); - for (jsize i = 0; i < count; ++i) { - AndroidInterface::JniLocalRef jstr( - ctx.env.jniEnv(), static_cast(ctx.env->GetObjectArrayElement(objArray.get(), i))); - if (!jstr.get()) { - qCWarning(AndroidSerialLog) << "Null string at index" << i; + qsizetype index = 0; + for (const QJniObject &portInfo : array) { + const qsizetype currentIndex = index++; + if (!portInfo.isValid()) { + qCWarning(AndroidSerialLog) << "Null UsbPortInfo element at index" << currentIndex; continue; } - const QStringList strList = QJniObject(jstr.get()).toString().split(QLatin1Char('\t')); + const QString deviceName = portInfo.callMethod("deviceName").toString(); + const QString productName = portInfo.callMethod("productName").toString(); + const QString manufacturerName = portInfo.callMethod("manufacturerName").toString(); + const QString serialNumber = portInfo.callMethod("serialNumber").toString(); + const jint productId = portInfo.callMethod("productId"); + const jint vendorId = portInfo.callMethod("vendorId"); - if (strList.size() < 6) { - qCWarning(AndroidSerialLog) << "Invalid device info at index" << i << ":" << strList; + if (env.checkAndClearExceptions()) { + qCWarning(AndroidSerialLog) << "Exception reading UsbPortInfo at index" << currentIndex; continue; } - bool pidOK, vidOK; - QSerialPortInfoPrivate info; - info.portName = QSerialPortInfoPrivate::portNameFromSystemLocation(strList[0]); - info.device = strList[0]; - info.description = strList[1]; - info.manufacturer = strList[2]; - info.serialNumber = strList[3]; - info.productIdentifier = strList[4].toInt(&pidOK); - info.hasProductIdentifier = (pidOK && (info.productIdentifier != INVALID_DEVICE_ID)); - info.vendorIdentifier = strList[5].toInt(&vidOK); - info.hasVendorIdentifier = (vidOK && (info.vendorIdentifier != INVALID_DEVICE_ID)); + QGCSerialPortInfo::Data data; + data.portName = portNameFromDevicePath(deviceName); + data.systemLocation = deviceName; + data.description = productName; + data.manufacturer = manufacturerName; + data.serialNumber = serialNumber; + data.productIdentifier = static_cast(productId); + data.hasProductIdentifier = (productId != INVALID_DEVICE_ID); + data.vendorIdentifier = static_cast(vendorId); + data.hasVendorIdentifier = (vendorId != INVALID_DEVICE_ID); - serialPortInfoList.append(info); + serialPortInfoList.append(QGCSerialPortInfo(std::move(data))); } - (void)ctx.env.checkAndClearExceptions(); + (void) env.checkAndClearExceptions(); return serialPortInfoList; } -// ---------------------------------------------------------------------------- -// Device ID / handle lookup -// ---------------------------------------------------------------------------- - -int getDeviceId(const QString& portName) -{ - const QJniObject name = QJniObject::fromString(portName); - if (!name.isValid()) { - qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in getDeviceId"; - return -1; - } - - JniContext ctx; - if (!getContext(ctx, "getDeviceId")) - return -1; - - jint result = -1; - if (!AndroidInterface::callStaticIntMethod(ctx.env, ctx.cls, s_methods.getDeviceId, "getDeviceId", - AndroidSerialLog(), result, name.object())) { - return -1; - } - - return static_cast(result); -} - -int getDeviceHandle(int deviceId) -{ - JniContext ctx; - if (!getContext(ctx, "getDeviceHandle")) - return -1; - - jint result = -1; - if (!AndroidInterface::callStaticIntMethod(ctx.env, ctx.cls, s_methods.getDeviceHandle, "getDeviceHandle", - AndroidSerialLog(), result, static_cast(deviceId))) { - return -1; - } - - return static_cast(result); -} - -// ---------------------------------------------------------------------------- -// Open / close / isOpen -// ---------------------------------------------------------------------------- - -int open(const QString& portName, QSerialPortPrivate* classPtr) -{ - if (!classPtr) { - qCWarning(AndroidSerialLog) << "open called with null serialPort"; - return INVALID_DEVICE_ID; - } - - const jlong token = lookupToken(classPtr); - if (token == 0) { - qCWarning(AndroidSerialLog) << "open called with unregistered pointer — call registerPointer first"; - return INVALID_DEVICE_ID; - } - - const QJniObject name = QJniObject::fromString(portName); - if (!name.isValid()) { - qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in open"; - return INVALID_DEVICE_ID; - } - - JniContext ctx; - if (!getContext(ctx, "open")) - return INVALID_DEVICE_ID; - - jint deviceId = INVALID_DEVICE_ID; - if (!AndroidInterface::callStaticIntMethod(ctx.env, ctx.cls, s_methods.open, "open", AndroidSerialLog(), deviceId, - name.object(), token)) { - return INVALID_DEVICE_ID; - } - - return static_cast(deviceId); -} - -bool close(int deviceId) -{ - JniContext ctx; - if (!getContext(ctx, "close")) - return false; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.close, "close", AndroidSerialLog(), - result, static_cast(deviceId))) { - return false; - } - - return (result == JNI_TRUE); -} - -bool isOpen(const QString& portName) -{ - const QJniObject name = QJniObject::fromString(portName); - if (!name.isValid()) { - qCWarning(AndroidSerialLog) << "Invalid QJniObject for portName in isOpen"; - return false; - } - - JniContext ctx; - if (!getContext(ctx, "isOpen")) - return false; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.isDeviceNameOpen, "isDeviceNameOpen", - AndroidSerialLog(), result, name.object())) { - return false; - } - - return (result == JNI_TRUE); -} - -// ---------------------------------------------------------------------------- -// Read / write -// ---------------------------------------------------------------------------- - -QByteArray read(int deviceId, int length, int timeout) -{ - JniContext ctx; - if (!getContext(ctx, "read")) - return QByteArray(); - - AndroidInterface::JniLocalRef jarray( - ctx.env.jniEnv(), static_cast( - ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.read, static_cast(deviceId), - static_cast(length), static_cast(timeout)))); - - if (!jarray.get()) { - qCWarning(AndroidSerialLog) << "read method returned null"; - (void)ctx.env.checkAndClearExceptions(); - return QByteArray(); - } - - if (ctx.env.checkAndClearExceptions()) { - qCWarning(AndroidSerialLog) << "Exception occurred while calling read"; - return QByteArray(); - } - - const jsize len = ctx.env->GetArrayLength(jarray.get()); - jbyte* const bytes = ctx.env->GetByteArrayElements(jarray.get(), nullptr); - if (!bytes) { - qCWarning(AndroidSerialLog) << "Failed to get byte array elements in read"; - return QByteArray(); - } - - const QByteArray data(reinterpret_cast(bytes), len); - ctx.env->ReleaseByteArrayElements(jarray.get(), bytes, JNI_ABORT); - - return data; -} - -int write(int deviceId, const char* data, int length, int timeout, bool async) -{ - if (!data || length <= 0) { - qCWarning(AndroidSerialLog) << "Invalid data or length in write"; - return -1; - } - - JniContext ctx; - if (!getContext(ctx, "write")) - return -1; - - AndroidInterface::JniLocalRef jarray(ctx.env.jniEnv(), - ctx.env->NewByteArray(static_cast(length))); - if (!jarray.get()) { - qCWarning(AndroidSerialLog) << "Failed to create jbyteArray in write"; - return -1; - } - - ctx.env->SetByteArrayRegion(jarray.get(), 0, static_cast(length), reinterpret_cast(data)); - if (ctx.env.checkAndClearExceptions()) { - qCWarning(AndroidSerialLog) << "Exception occurred while setting byte array region in write"; - return -1; - } - - jint result; - if (async) { - result = ctx.env->CallStaticIntMethod(ctx.cls, s_methods.writeAsync, static_cast(deviceId), jarray.get(), - static_cast(timeout)); - } else { - result = ctx.env->CallStaticIntMethod(ctx.cls, s_methods.write, static_cast(deviceId), jarray.get(), - static_cast(length), static_cast(timeout)); - } - - if (ctx.env.checkAndClearExceptions()) { - qCWarning(AndroidSerialLog) << "Exception occurred while calling write/writeAsync"; - return -1; - } - - return static_cast(result); -} - -// ---------------------------------------------------------------------------- -// Port configuration -// ---------------------------------------------------------------------------- - -bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity) -{ - JniContext ctx; - if (!getContext(ctx, "setParameters")) - return false; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.setParameters, "setParameters", - AndroidSerialLog(), result, static_cast(deviceId), - static_cast(baudRate), static_cast(dataBits), - static_cast(stopBits), static_cast(parity))) { - return false; - } - - return (result == JNI_TRUE); -} - -// ---------------------------------------------------------------------------- -// Control line helpers (DRY macro for bool getters) -// ---------------------------------------------------------------------------- - -static bool callBoolMethod(jmethodID method, int deviceId, const char* name) -{ - JniContext ctx; - if (!getContext(ctx, name)) - return false; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, method, name, AndroidSerialLog(), result, - static_cast(deviceId))) { - return false; - } - - return (result == JNI_TRUE); -} - -static bool callBoolSetMethod(jmethodID method, int deviceId, bool set, const char* name) -{ - JniContext ctx; - if (!getContext(ctx, name)) - return false; - - const jboolean jSet = set ? JNI_TRUE : JNI_FALSE; - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, method, name, AndroidSerialLog(), result, - static_cast(deviceId), jSet)) { - return false; - } - - return (result == JNI_TRUE); -} - -// ---------------------------------------------------------------------------- -// Control lines -// ---------------------------------------------------------------------------- - -bool getCarrierDetect(int deviceId) -{ - return callBoolMethod(s_methods.getCarrierDetect, deviceId, "getCarrierDetect"); -} - -bool getClearToSend(int deviceId) -{ - return callBoolMethod(s_methods.getClearToSend, deviceId, "getClearToSend"); -} - -bool getDataSetReady(int deviceId) -{ - return callBoolMethod(s_methods.getDataSetReady, deviceId, "getDataSetReady"); -} - -bool getDataTerminalReady(int deviceId) -{ - return callBoolMethod(s_methods.getDataTerminalReady, deviceId, "getDataTerminalReady"); -} - -bool getRingIndicator(int deviceId) -{ - return callBoolMethod(s_methods.getRingIndicator, deviceId, "getRingIndicator"); -} - -bool getRequestToSend(int deviceId) -{ - return callBoolMethod(s_methods.getRequestToSend, deviceId, "getRequestToSend"); -} - -bool setDataTerminalReady(int deviceId, bool set) -{ - return callBoolSetMethod(s_methods.setDataTerminalReady, deviceId, set, "setDataTerminalReady"); -} - -bool setRequestToSend(int deviceId, bool set) -{ - return callBoolSetMethod(s_methods.setRequestToSend, deviceId, set, "setRequestToSend"); -} - -QSerialPort::PinoutSignals getControlLines(int deviceId) -{ - JniContext ctx; - if (!getContext(ctx, "getControlLines")) - return QSerialPort::PinoutSignals(); - - AndroidInterface::JniLocalRef jarray( - ctx.env.jniEnv(), static_cast(ctx.env->CallStaticObjectMethod(ctx.cls, s_methods.getControlLines, - static_cast(deviceId)))); - if (!jarray.get()) { - qCWarning(AndroidSerialLog) << "getControlLines returned null"; - (void)ctx.env.checkAndClearExceptions(); - return QSerialPort::PinoutSignals(); - } - - if (ctx.env.checkAndClearExceptions()) { - qCWarning(AndroidSerialLog) << "Exception occurred while calling getControlLines"; - return QSerialPort::PinoutSignals(); - } - - jint* const ints = ctx.env->GetIntArrayElements(jarray.get(), nullptr); - if (!ints) { - qCWarning(AndroidSerialLog) << "Failed to get int array elements in getControlLines"; - return QSerialPort::PinoutSignals(); - } - - const jsize len = ctx.env->GetArrayLength(jarray.get()); - QSerialPort::PinoutSignals data = QSerialPort::PinoutSignals(); - - for (jsize i = 0; i < len; ++i) { - switch (ints[i]) { - case RtsControlLine: - data |= QSerialPort::RequestToSendSignal; - break; - case CtsControlLine: - data |= QSerialPort::ClearToSendSignal; - break; - case DtrControlLine: - data |= QSerialPort::DataTerminalReadySignal; - break; - case DsrControlLine: - data |= QSerialPort::DataSetReadySignal; - break; - case CdControlLine: - data |= QSerialPort::DataCarrierDetectSignal; - break; - case RiControlLine: - data |= QSerialPort::RingIndicatorSignal; - break; - default: - qCWarning(AndroidSerialLog) << "Unknown ControlLine value:" << ints[i]; - break; - } - } - - ctx.env->ReleaseIntArrayElements(jarray.get(), ints, JNI_ABORT); - (void)ctx.env.checkAndClearExceptions(); - - return data; -} - -// ---------------------------------------------------------------------------- -// Flow control -// ---------------------------------------------------------------------------- - -int getFlowControl(int deviceId) -{ - JniContext ctx; - if (!getContext(ctx, "getFlowControl")) - return QSerialPort::NoFlowControl; - - jint flowControl = QSerialPort::NoFlowControl; - if (!AndroidInterface::callStaticIntMethod(ctx.env, ctx.cls, s_methods.getFlowControl, "getFlowControl", - AndroidSerialLog(), flowControl, static_cast(deviceId))) { - return QSerialPort::NoFlowControl; - } - - return static_cast(flowControl); -} - -bool setFlowControl(int deviceId, int flowControl) -{ - JniContext ctx; - if (!getContext(ctx, "setFlowControl")) - return false; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.setFlowControl, "setFlowControl", - AndroidSerialLog(), result, static_cast(deviceId), - static_cast(flowControl))) { - return false; - } - - return result == JNI_TRUE; -} - -// ---------------------------------------------------------------------------- -// Buffer / break -// ---------------------------------------------------------------------------- - -bool purgeBuffers(int deviceId, bool input, bool output) -{ - JniContext ctx; - if (!getContext(ctx, "purgeBuffers")) - return false; - - const jboolean jInput = input ? JNI_TRUE : JNI_FALSE; - const jboolean jOutput = output ? JNI_TRUE : JNI_FALSE; - - jboolean result = JNI_FALSE; - if (!AndroidInterface::callStaticBooleanMethod(ctx.env, ctx.cls, s_methods.purgeBuffers, "purgeBuffers", - AndroidSerialLog(), result, static_cast(deviceId), jInput, - jOutput)) { - return false; - } - - return (result == JNI_TRUE); -} - -bool setBreak(int deviceId, bool set) -{ - return callBoolSetMethod(s_methods.setBreak, deviceId, set, "setBreak"); -} - -// ---------------------------------------------------------------------------- -// IO manager (read thread) -// ---------------------------------------------------------------------------- - -bool startReadThread(int deviceId) -{ - return callBoolMethod(s_methods.startIoManager, deviceId, "startIoManager"); -} - -bool stopReadThread(int deviceId) -{ - return callBoolMethod(s_methods.stopIoManager, deviceId, "stopIoManager"); -} - -bool readThreadRunning(int deviceId) -{ - return callBoolMethod(s_methods.ioManagerRunning, deviceId, "ioManagerRunning"); -} - } // namespace AndroidSerial diff --git a/src/Android/AndroidSerial.h b/src/Android/AndroidSerial.h index 8ef2191e0ec0..bbd3c7b3b07e 100644 --- a/src/Android/AndroidSerial.h +++ b/src/Android/AndroidSerial.h @@ -1,89 +1,41 @@ #pragma once -#include +#include #include -#include -#include -class QSerialPortPrivate; +class QGCSerialPortInfo; namespace AndroidSerial { -enum DataBits -{ - Data5 = 5, - Data6 = 6, - Data7 = 7, - Data8 = 8 -}; -enum Parity -{ - NoParity = 0, - OddParity, - EvenParity, - MarkParity, - SpaceParity +// Wire-format values matching upstream usb-serial-for-android. DataBits and StopBits +// are intentionally absent: their numeric values match QSerialPort::DataBits / +// QSerialPort::StopBits exactly, so callers static_cast directly. +enum Parity { NoParity = 0, OddParity, EvenParity, MarkParity, SpaceParity }; +enum ControlLine { RtsControlLine = 0, CtsControlLine, DtrControlLine, DsrControlLine, CdControlLine, RiControlLine }; +enum FlowControl { + NoFlowControl = 0, RtsCtsFlowControl, DtrDsrFlowControl, XonXoffFlowControl, XonXoffInlineFlowControl }; -enum StopBits -{ - OneStop = 1, - OneAndHalfStop = 3, - TwoStop = 2 +// Mirrors SerialConstants.EXC_* in Java. Drives QSerialPort::SerialPortError mapping +// in qserialport_android.cpp::exceptionNotification — keep in sync with Java side. +enum class JavaExceptionKind : int { + Unknown = 0, + Resource = 1, + Permission = 2, + OpenFailed = 3, }; -enum ControlLine -{ - RtsControlLine = 0, - CtsControlLine, - DtrControlLine, - DsrControlLine, - CdControlLine, - RiControlLine -}; +constexpr qint64 MAX_READ_SIZE = 16 * 1024; +constexpr int INVALID_DEVICE_ID = 0; -enum FlowControl -{ - NoFlowControl = 0, - RtsCtsFlowControl, - DtrDsrFlowControl, - XonXoffFlowControl, - XonXoffInlineFlowControl +struct SerialParameters { + qint32 baudRate; + int dataBits; + int stopBits; + int parity; }; -constexpr char CHAR_XON = 17; -constexpr char CHAR_XOFF = 19; - -constexpr const char* kJniUsbSerialManagerClassName = "org/mavlink/qgroundcontrol/QGCUsbSerialManager"; - -void setNativeMethods(); -QList availableDevices(); -int getDeviceId(const QString& portName); -int getDeviceHandle(int deviceId); -int open(const QString& portName, QSerialPortPrivate* classPtr); -bool close(int deviceId); -bool isOpen(const QString& portName); -QByteArray read(int deviceId, int length, int timeout); -int write(int deviceId, const char* data, int length, int timeout, bool async); -bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity); -bool getCarrierDetect(int deviceId); -bool getClearToSend(int deviceId); -bool getDataSetReady(int deviceId); -bool getDataTerminalReady(int deviceId); -bool setDataTerminalReady(int deviceId, bool set); -bool getRingIndicator(int deviceId); -bool getRequestToSend(int deviceId); -bool setRequestToSend(int deviceId, bool set); -QSerialPort::PinoutSignals getControlLines(int deviceId); -int getFlowControl(int deviceId); -bool setFlowControl(int deviceId, int flowControl); -bool purgeBuffers(int deviceId, bool input, bool output); -bool setBreak(int deviceId, bool set); -bool startReadThread(int deviceId); -bool stopReadThread(int deviceId); -bool readThreadRunning(int deviceId); +void initialize(); +QList availableDevices(); -void registerPointer(QSerialPortPrivate* ptr); -void unregisterPointer(QSerialPortPrivate* ptr); -void cleanupJniCache(); } // namespace AndroidSerial diff --git a/src/Android/CMakeLists.txt b/src/Android/CMakeLists.txt index 1b3feb558008..0aa9d635bd84 100644 --- a/src/Android/CMakeLists.txt +++ b/src/Android/CMakeLists.txt @@ -3,7 +3,12 @@ # Android platform-specific initialization and interfaces # ============================================================================ -# Only build on Android platforms +# qtandroidserialport is built on both Android and host. On host it exposes the +# JNI-free portion of the backend so QGCAndroidSerialPort's production logic can +# be exercised via MockQSerialPortEngine (test/Comms/Android). +add_subdirectory(qtandroidserialport) + +# The rest of the Android module is Android-only. if(NOT ANDROID) return() endif() @@ -15,17 +20,14 @@ target_sources(${CMAKE_PROJECT_NAME} AndroidInit.cc AndroidInterface.cc AndroidInterface.h + AndroidLogSink.cc + AndroidLogSink.h AndroidSerial.cc AndroidSerial.h ) target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) -# ---------------------------------------------------------------------------- -# Android Serial Port Support -# ---------------------------------------------------------------------------- -add_subdirectory(qtandroidserialport) - # ---------------------------------------------------------------------------- # Qt Android Extensions (2GIS) — selective compile # https://github.com/2gis/qtandroidextensions diff --git a/src/Android/qtandroidserialport/CMakeLists.txt b/src/Android/qtandroidserialport/CMakeLists.txt index c2e91cf55cec..6ef55faded51 100644 --- a/src/Android/qtandroidserialport/CMakeLists.txt +++ b/src/Android/qtandroidserialport/CMakeLists.txt @@ -1,41 +1,65 @@ # ============================================================================ -# Qt Android Serial Port — vendored from Qt SerialPort +# QGC Android serial port — vendored Qt SerialPort fully replaced. +# +# On Android, QGCAndroidSerialPort (QIODevice subclass) talks to the Java USB +# serial layer via QAndroidSerialEngine. On host, the same QGCAndroidSerialPort +# class is built without the JNI engine so its production logic can be tested +# via MockQSerialPortEngine (test/Comms/Android). QGCSerialPortAdapter +# (src/Comms) is the single serial-port type used by SerialLink / Bootloader / +# GPSProvider / NMEA — see its header for the full contract. # ============================================================================ -if(NOT ANDROID) - return() -endif() +if(ANDROID) + qt_add_library(QGCAndroidSerialPort STATIC + iqserialportengine_p.h + qandroidserialenginereceiver_p.h + qandroidserialengine.cpp + qandroidserialengine_p.h + QGCAndroidSerialPort.cc + QGCAndroidSerialPort.h + ) + + target_link_libraries(QGCAndroidSerialPort + PUBLIC + Qt6::Core + PRIVATE + QGCLogging + ) -qt_add_library(QGCAndroidSerialPort STATIC - qserialport.cpp - qserialport.h - qserialport_android.cpp - qserialport_p.h - qserialportglobal.h - qserialportinfo.cpp - qserialportinfo.h - qserialportinfo_p.h - qserialportinfo_android.cpp - qtserialportexports.h - qtserialportversion.h -) + target_include_directories(QGCAndroidSerialPort + PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} + PRIVATE + ${CMAKE_SOURCE_DIR}/src/Android + ) -target_link_libraries(QGCAndroidSerialPort - PUBLIC - Qt6::Core - PRIVATE - Qt6::CorePrivate # , qproperty_p.h - QGCLogging # QGCLoggingCategory.h -) + target_link_libraries(${CMAKE_PROJECT_NAME} PRIVATE QGCAndroidSerialPort) +else() + # Host build: only the JNI-free portion of the backend. Tests inject a + # MockQSerialPortEngine via QGCAndroidSerialPortFactory::setEngineFactory. + qt_add_library(QGCAndroidSerialPort STATIC + iqserialportengine_p.h + qandroidserialenginereceiver_p.h + QGCAndroidSerialPort.cc + QGCAndroidSerialPort.h + ) -target_include_directories(QGCAndroidSerialPort - PUBLIC - ${CMAKE_CURRENT_SOURCE_DIR} - PRIVATE - ${CMAKE_SOURCE_DIR}/src/Android # AndroidSerial.h -) + target_link_libraries(QGCAndroidSerialPort + PUBLIC + Qt6::Core + PRIVATE + QGCLogging + ) -# TODO: Enable I/O device debugging -# target_compile_definitions(QGCAndroidSerialPort PRIVATE QIODEVICE_DEBUG) + target_include_directories(QGCAndroidSerialPort + PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} + PRIVATE + ${CMAKE_SOURCE_DIR}/src/Android + ) -target_link_libraries(${CMAKE_PROJECT_NAME} PRIVATE QGCAndroidSerialPort) + # QGCSerialPortAdapter (src/Comms) references QGCAndroidSerialPort symbols on host + # as well — needed for the setForceAndroidBackendForTests path that lets host tests + # exercise the Android backend via MockQSerialPortEngine. + target_link_libraries(${CMAKE_PROJECT_NAME} PRIVATE QGCAndroidSerialPort) +endif() diff --git a/src/Android/qtandroidserialport/QGCAndroidSerialPort.cc b/src/Android/qtandroidserialport/QGCAndroidSerialPort.cc new file mode 100644 index 000000000000..560d9806e2be --- /dev/null +++ b/src/Android/qtandroidserialport/QGCAndroidSerialPort.cc @@ -0,0 +1,833 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#include "QGCAndroidSerialPort.h" + +#include "AndroidSerial.h" +#include "QGCLoggingCategory.h" +#ifdef Q_OS_ANDROID +#include "qandroidserialengine_p.h" +#endif + +#include +#include +#include +#include +#include + +#include +#include +#include + +using namespace std::chrono_literals; + +QGC_LOGGING_CATEGORY(QGCAndroidSerialPortLog, "Android.Serial.Port") + +// Per-call sync drain cap. Matches MAX_SYNC_WRITE_CHUNK in legacy qserialport_p.h: +// 16 KB amortizes JNI + bulkTransfer setup overhead vs 4 KB; on saturated CDC links the +// per-call time scales sub-linearly with chunk size (most cost is the round-trip ACK). +namespace { +constexpr qint64 kMaxSyncWriteChunk = 16 * 1024; +constexpr int kDefaultWriteTimeoutMs = 5000; + +int parityToWire(QGCParity parity) +{ + switch (parity) { + case QGCParity::None: return AndroidSerial::NoParity; + case QGCParity::Odd: return AndroidSerial::OddParity; + case QGCParity::Even: return AndroidSerial::EvenParity; + case QGCParity::Mark: return AndroidSerial::MarkParity; + case QGCParity::Space: return AndroidSerial::SpaceParity; + } + return AndroidSerial::NoParity; +} + +int flowControlToWire(QGCFlowControl fc) +{ + switch (fc) { + case QGCFlowControl::None: return AndroidSerial::NoFlowControl; + case QGCFlowControl::HardwareRtsCts: return AndroidSerial::RtsCtsFlowControl; + case QGCFlowControl::SoftwareXonXoff: return AndroidSerial::XonXoffFlowControl; + } + return AndroidSerial::NoFlowControl; +} + +// Single mapping point for refining JavaExceptionKind → QGCSerialPortError as new +// exception kinds emerge. Mirrors the legacy exceptionKindToErrorCode(). +QGCSerialPortError exceptionKindToError(AndroidSerial::JavaExceptionKind kind) +{ + switch (kind) { + case AndroidSerial::JavaExceptionKind::Resource: return QGCSerialPortError::ResourceUnavailable; + case AndroidSerial::JavaExceptionKind::Permission: return QGCSerialPortError::PermissionDenied; + case AndroidSerial::JavaExceptionKind::OpenFailed: return QGCSerialPortError::OpenFailed; + case AndroidSerial::JavaExceptionKind::Unknown: return QGCSerialPortError::Unknown; + } + return QGCSerialPortError::Unknown; +} +} // namespace + +// ============================================================================ +// Factory +// ============================================================================ + +namespace { +// Default engine factory: instantiates the JNI-backed engine on Android, returns nullptr on +// host (where tests must inject MockQSerialPortEngine via setEngineFactory before constructing +// a QGCAndroidSerialPort). Keeps QGCAndroidSerialPort.cc host-buildable so production logic +// can be exercised without JNI. +QGCAndroidSerialPortFactory::EngineFactory defaultFactory() +{ +#ifdef Q_OS_ANDROID + return [](QAndroidSerialEngineReceiver* sink, QObject* owner) { + return std::unique_ptr(new QAndroidSerialEngine(sink, owner)); + }; +#else + return [](QAndroidSerialEngineReceiver*, QObject*) { + return std::unique_ptr{}; + }; +#endif +} +} // namespace + +QGCAndroidSerialPortFactory::EngineFactory& QGCAndroidSerialPortFactory::_engineFactory() +{ + static EngineFactory factory = defaultFactory(); + return factory; +} + +void QGCAndroidSerialPortFactory::setEngineFactory(EngineFactory factory) +{ + _engineFactory() = factory ? std::move(factory) : defaultFactory(); +} + +void QGCAndroidSerialPortFactory::resetEngineFactory() +{ + setEngineFactory(EngineFactory{}); +} + +// ============================================================================ +// Construction +// ============================================================================ + +QGCAndroidSerialPort::QGCAndroidSerialPort(QObject* parent) + : QIODevice(parent) +{ +} + +QGCAndroidSerialPort::QGCAndroidSerialPort(const QString& systemLocation, QObject* parent) + : QIODevice(parent) + , _systemLocation(systemLocation) +{ +} + +QGCAndroidSerialPort::~QGCAndroidSerialPort() +{ + if (isOpen()) { + close(); + } +} + +// ============================================================================ +// Lifecycle +// ============================================================================ + +bool QGCAndroidSerialPort::open(QIODeviceBase::OpenMode mode) +{ + if (isOpen()) { + _setError(QGCSerialPortError::OpenFailed, tr("Device is already open")); + return false; + } + + static const OpenMode kUnsupported = Append | Truncate | Text | Unbuffered; + if ((mode & kUnsupported) || mode == NotOpen) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Unsupported open mode")); + return false; + } + + qCDebug(QGCAndroidSerialPortLog) << "Opening" << _systemLocation; + + clearError(); + + const AndroidSerial::SerialParameters params{ + .baudRate = _baudRate, + .dataBits = static_cast(_dataBits), + .stopBits = static_cast(_stopBits), + .parity = parityToWire(_parity), + }; + + _engine = QGCAndroidSerialPortFactory::_engineFactory()(this, this); + if (!_engine) { + qCWarning(QGCAndroidSerialPortLog) << "Engine factory returned null for" << _systemLocation; + _setError(QGCSerialPortError::OpenFailed, tr("Failed to construct serial engine")); + return false; + } + _engine->setReadBufferMaxSize(_readBufferMaxSize); + + // assertDtr=true: CP210x / CH340 chips gate UART output on DTR. SerialLink later + // resets DTR per dtrForceLow configuration. + if (!_engine->open(_systemLocation, params, flowControlToWire(_flowControl), /*assertDtr=*/true)) { + qCWarning(QGCAndroidSerialPortLog) << "Error opening" << _systemLocation; + _setError(QGCSerialPortError::OpenFailed, tr("Device not found: %1").arg(_systemLocation)); + _engine.reset(); + return false; + } + + if (_engine->deviceHandle() == -1) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to get device handle for" << _systemLocation; + _setError(QGCSerialPortError::OpenFailed, tr("Failed to obtain device handle")); + close(); + return false; + } + + if (mode & QIODevice::ReadOnly) { + if (!_startAsyncRead()) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to start async read for" << _systemLocation; + close(); + return false; + } + } + + // Owner-thread write timer. QChronoTimer is thread-affine — start() from a foreign + // thread is not safe, so create here in open() rather than lazily in writeData(). + if (!_writeTimer) { + _writeTimer = std::make_unique(this); + _writeTimer->setSingleShot(true); + connect(_writeTimer.get(), &QChronoTimer::timeout, this, + &QGCAndroidSerialPort::_drainWriteBuffer); + } + + QIODevice::open(mode); + + // Purge stale buffers AFTER QIODevice::open so clear()'s isOpen() guard doesn't + // leave a stale NotOpen error on a successful open. + (void)clear(); + return true; +} + +void QGCAndroidSerialPort::close() +{ + if (!isOpen()) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return; + } + + qCDebug(QGCAndroidSerialPortLog) << "Closing" << _systemLocation; + + // Set BEFORE aboutToClose so any synchronously-dispatched exception inside the slot + // (e.g. a queued Resource exception that races the close) is also suppressed. + _expectClosure = true; + + // QIODevice contract: aboutToClose fires BEFORE the device is torn down so slots + // can still drain pending data. (Fixes the inversion in the legacy QSerialPortPrivate + // that called d->close() before QIODevice::close(), flagged by qt-qml-expert.) + emit aboutToClose(); + + (void)_stopAsyncRead(); + + _writeTimer.reset(); + + if (_engine) { + if (!_engine->isOpen()) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to close device, port not open"; + } + _engine.reset(); + } + + // Re-entrancy guards reset so a reopen of this instance starts clean. + _emittedReadyRead = false; + _emittedBytesWritten = false; + _expectClosure = false; + _breakEnabled = false; + _readBuffer.clear(); + _readOffset = 0; + _writeBuffer.clear(); + + QIODevice::close(); + + // Notify consumers (e.g. bootloader upload) that no more reads will arrive. + emit readChannelFinished(); +} + +// ============================================================================ +// QAndroidSerialEngineReceiver — engine has marshaled to the owner thread. +// ============================================================================ + +void QGCAndroidSerialPort::dataReady(QByteArray&& bytes) +{ + if (bytes.isEmpty()) return; + // Compact the dead prefix only when it accounts for half the backing buffer or more — + // bounds wasted memory without paying for a memmove on every append. + if (_readOffset > 0 && _readOffset >= _readBuffer.size() / 2) { + _readBuffer.remove(0, _readOffset); + _readOffset = 0; + } + _readBuffer.append(std::move(bytes)); + if (!_emittedReadyRead) { + _emittedReadyRead = true; + emit readyRead(); + _emittedReadyRead = false; + } +} + +void QGCAndroidSerialPort::closeNotification() +{ + if (isOpen()) { + qCDebug(QGCAndroidSerialPortLog) << "Closing serial port" << _systemLocation + << "after disconnect"; + // Peer is gone — draining queued writes spams "null port" warnings. + _writeBuffer.clear(); + close(); + } else { + qCDebug(QGCAndroidSerialPortLog) << "Serial port" << _systemLocation + << "already closed at disconnect"; + } +} + +void QGCAndroidSerialPort::exceptionNotification(AndroidSerial::JavaExceptionKind kind, + const QString& message) +{ + if (_expectClosure && kind == AndroidSerial::JavaExceptionKind::Resource) { + qCDebug(QGCAndroidSerialPortLog) << "Suppressed expected Resource exception on" + << _systemLocation << "during close:" << message; + return; + } + + qCWarning(QGCAndroidSerialPortLog) << "Exception arrived on" << _systemLocation + << "kind=" << static_cast(kind) << ":" << message; + + _setError(exceptionKindToError(kind), message); + + // Resource exceptions = device unreachable. Close eagerly instead of waiting for the + // DETACH-driven closeNotification — otherwise queued writes keep firing _drainWriteBuffer + // → engine->writeSync → "null port" warns. + if (kind == AndroidSerial::JavaExceptionKind::Resource && isOpen()) { + _writeBuffer.clear(); + close(); + } +} + +// ============================================================================ +// QIODevice I/O +// ============================================================================ + +qint64 QGCAndroidSerialPort::readData(char* data, qint64 maxSize) +{ + if (!data || maxSize <= 0) return 0; + const qsizetype available = _readBuffer.size() - _readOffset; + if (available <= 0) return 0; + + const qint64 toCopy = qMin(maxSize, available); + std::memcpy(data, _readBuffer.constData() + _readOffset, toCopy); + _readOffset += toCopy; + // Fully drained — drop the buffer outright so we don't carry a stale allocation. + if (_readOffset >= _readBuffer.size()) { + _readBuffer.clear(); + _readOffset = 0; + } + return toCopy; +} + +qint64 QGCAndroidSerialPort::readLineData(char* data, qint64 maxSize) +{ + return QIODevice::readLineData(data, maxSize); +} + +qint64 QGCAndroidSerialPort::writeData(const char* data, qint64 maxSize) +{ + if (!data || maxSize <= 0) { + qCWarning(QGCAndroidSerialPortLog) << "Invalid data or size in writeData for" << _systemLocation; + _setError(QGCSerialPortError::Write, tr("Invalid data or size")); + return -1; + } + + // Cap check first — if writeBufferMaxSize is set and the buffer is at capacity, + // returning 0 would be read as "no error, no bytes written" and silently drop the + // payload. Signal Write error and return -1 to match upstream qserialport_win.cpp. + const qint64 toAppend = _writeBufferMaxSize + ? qMin(maxSize, _writeBufferMaxSize - _writeBuffer.size()) + : maxSize; + if (toAppend <= 0) { + qCWarning(QGCAndroidSerialPortLog) << "writeBuffer full (" + << _writeBuffer.size() << "/" + << _writeBufferMaxSize << "bytes) on" + << _systemLocation << ", dropping write of" + << maxSize << "bytes"; + _setError(QGCSerialPortError::Write, tr("Write buffer full")); + return -1; + } + + _writeBuffer.append(data, toAppend); + + // Fresh writes drain on next event-loop tick (interval 0). Partial-write reschedules + // in _drainWriteBuffer() use a 5 ms back-off so backpressure doesn't spin the loop. + if (_writeTimer && !_writeTimer->isActive()) { + _writeTimer->setInterval(0ns); + _writeTimer->start(); + } + + return toAppend; +} + +void QGCAndroidSerialPort::_drainWriteBuffer() +{ + qint64 totalWritten = 0; + bool writeFailed = false; + + while (!_writeBuffer.isEmpty()) { + const qint64 chunk = qMin(_writeBuffer.size(), kMaxSyncWriteChunk); + const qint64 written = _writeToEngine(_writeBuffer.constData(), chunk, + kDefaultWriteTimeoutMs, /*async=*/false); + if (written <= 0) { + // Peer gone — drop queued bytes. Retrying spins the event loop and starves + // the queued exception/close metaCalls that would otherwise tear the port down. + _writeBuffer.clear(); + writeFailed = true; + break; + } + _writeBuffer.remove(0, written); + totalWritten += written; + } + + if (totalWritten > 0 && !_emittedBytesWritten) { + _emittedBytesWritten = true; + emit bytesWritten(totalWritten); + _emittedBytesWritten = false; + } + + if (!writeFailed && !_writeBuffer.isEmpty() && _writeTimer) { + _writeTimer->setInterval(5ms); + _writeTimer->start(); + } +} + +qint64 QGCAndroidSerialPort::_writeToEngine(const char* data, qint64 maxSize, int timeout, bool async) +{ + if (!_engine) return -1; + + // JNI layer uses jint (32-bit); cap to INT_MAX to avoid silent truncation. + const int capped = static_cast(qMin(maxSize, static_cast(INT_MAX))); + const QSpan chunk{data, capped}; + const qint64 result = async ? _engine->writeAsync(chunk, timeout) + : _engine->writeSync(chunk, timeout); + if (result < 0) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to write to" << _systemLocation; + _setError(QGCSerialPortError::Write, tr("Failed to write to port")); + } + return result; +} + +// ============================================================================ +// Read thread +// ============================================================================ + +bool QGCAndroidSerialPort::_startAsyncRead() +{ + if (!_engine) return false; + if (_engine->readThreadRunning()) return true; + if (!_engine->startReadThread()) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to start async read thread for" + << _systemLocation; + _setError(QGCSerialPortError::Read, tr("Failed to start async read")); + return false; + } + return true; +} + +bool QGCAndroidSerialPort::_stopAsyncRead() +{ + if (!_engine) return true; + if (!_engine->readThreadRunning()) return true; + if (!_engine->stopReadThread()) { + qCWarning(QGCAndroidSerialPortLog) << "Failed to stop async read thread for" + << _systemLocation; + _setError(QGCSerialPortError::Read, tr("Failed to stop async read")); + return false; + } + return true; +} + +// ============================================================================ +// Blocking waits +// ============================================================================ + +bool QGCAndroidSerialPort::waitForReadyRead(int msecs) +{ + if (_readBuffer.size() - _readOffset > 0) return true; + if (!_engine) return false; + + // Drain pending writes — the write timer needs the event loop, and a blocked caller + // (e.g. Bootloader::_read) doesn't pump it. + if (!_writeBuffer.isEmpty()) { + _drainWriteBuffer(); + } + + QByteArray data = _engine->waitForReadyRead(msecs, _readBuffer.size() - _readOffset); + if (data.isEmpty()) { + qCWarning(QGCAndroidSerialPortLog) << "Timeout while waiting for ready read on" + << _systemLocation; + _setError(QGCSerialPortError::Timeout, tr("Timeout while waiting for ready read")); + return false; + } + + if (_readOffset > 0 && _readOffset >= _readBuffer.size() / 2) { + _readBuffer.remove(0, _readOffset); + _readOffset = 0; + } + _readBuffer.append(std::move(data)); + return true; +} + +bool QGCAndroidSerialPort::waitForBytesWritten(int msecs) +{ + QDeadlineTimer deadline(msecs); + while (!_writeBuffer.isEmpty()) { + const int remaining = deadline.isForever() ? kDefaultWriteTimeoutMs + : static_cast(deadline.remainingTime()); + if (!deadline.isForever() && remaining <= 0) { + _setError(QGCSerialPortError::Timeout, tr("Timeout while waiting for bytes written")); + return false; + } + + const qint64 chunk = qMin(_writeBuffer.size(), kMaxSyncWriteChunk); + const qint64 written = _writeToEngine(_writeBuffer.constData(), chunk, + qMax(1, remaining), /*async=*/false); + if (written <= 0) return false; + + _writeBuffer.remove(0, written); + if (!_emittedBytesWritten) { + _emittedBytesWritten = true; + emit bytesWritten(written); + _emittedBytesWritten = false; + } + } + return true; +} + +// ============================================================================ +// Buffers / state queries +// ============================================================================ + +qint64 QGCAndroidSerialPort::bytesAvailable() const +{ + return (_readBuffer.size() - _readOffset) + QIODevice::bytesAvailable(); +} + +qint64 QGCAndroidSerialPort::bytesToWrite() const +{ + return _writeBuffer.size() + QIODevice::bytesToWrite(); +} + +bool QGCAndroidSerialPort::canReadLine() const +{ + // Search only the live tail — the dead prefix [0, _readOffset) was already consumed. + const QByteArrayView tail(_readBuffer.constData() + _readOffset, + _readBuffer.size() - _readOffset); + return tail.contains('\n') || QIODevice::canReadLine(); +} + +void QGCAndroidSerialPort::setReadBufferSize(qint64 size) +{ + _readBufferMaxSize = size; + if (_engine) _engine->setReadBufferMaxSize(size); +} + +void QGCAndroidSerialPort::setWriteBufferSize(qint64 size) +{ + _writeBufferMaxSize = size; +} + +// ============================================================================ +// Port identification +// ============================================================================ + +void QGCAndroidSerialPort::setSystemLocation(const QString& location) +{ + _systemLocation = location; +} + +QString QGCAndroidSerialPort::portName() const +{ + // System location is typically "/dev/bus/usb//" — keep last component. + const int idx = _systemLocation.lastIndexOf(QLatin1Char('/')); + return idx >= 0 ? _systemLocation.mid(idx + 1) : _systemLocation; +} + +// ============================================================================ +// Configuration setters — cached when closed, applied to engine when open. +// ============================================================================ + +bool QGCAndroidSerialPort::setBaudRate(qint32 baudRate) +{ + if (baudRate <= 0) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Invalid baud rate value")); + return false; + } + if (_baudRate == baudRate) return true; + if (isOpen()) { + if (!_engine) return false; + const AndroidSerial::SerialParameters params{ + .baudRate = baudRate, + .dataBits = static_cast(_dataBits), + .stopBits = static_cast(_stopBits), + .parity = parityToWire(_parity), + }; + if (!_engine->setParameters(params)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set baud rate")); + return false; + } + } + _baudRate = baudRate; + emit baudRateChanged(baudRate); + return true; +} + +bool QGCAndroidSerialPort::setDataBits(QGCDataBits dataBits) +{ + if (_dataBits == dataBits) return true; + if (isOpen()) { + if (!_engine) return false; + const AndroidSerial::SerialParameters params{ + .baudRate = _baudRate, + .dataBits = static_cast(dataBits), + .stopBits = static_cast(_stopBits), + .parity = parityToWire(_parity), + }; + if (!_engine->setParameters(params)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set data bits")); + return false; + } + } + _dataBits = dataBits; + emit dataBitsChanged(dataBits); + return true; +} + +bool QGCAndroidSerialPort::setParity(QGCParity parity) +{ + if (_parity == parity) return true; + if (isOpen()) { + if (!_engine) return false; + const AndroidSerial::SerialParameters params{ + .baudRate = _baudRate, + .dataBits = static_cast(_dataBits), + .stopBits = static_cast(_stopBits), + .parity = parityToWire(parity), + }; + if (!_engine->setParameters(params)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set parity")); + return false; + } + } + _parity = parity; + emit parityChanged(parity); + return true; +} + +bool QGCAndroidSerialPort::setStopBits(QGCStopBits stopBits) +{ + if (_stopBits == stopBits) return true; + if (isOpen()) { + if (!_engine) return false; + const AndroidSerial::SerialParameters params{ + .baudRate = _baudRate, + .dataBits = static_cast(_dataBits), + .stopBits = static_cast(stopBits), + .parity = parityToWire(_parity), + }; + if (!_engine->setParameters(params)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set stop bits")); + return false; + } + } + _stopBits = stopBits; + emit stopBitsChanged(stopBits); + return true; +} + +bool QGCAndroidSerialPort::setSerialParameters(qint32 baudRate, QGCDataBits dataBits, + QGCStopBits stopBits, QGCParity parity) +{ + if (baudRate <= 0) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Invalid baud rate value")); + return false; + } + const bool baudDiff = _baudRate != baudRate; + const bool dataDiff = _dataBits != dataBits; + const bool stopDiff = _stopBits != stopBits; + const bool parityDiff = _parity != parity; + if (!baudDiff && !dataDiff && !stopDiff && !parityDiff) return true; + if (isOpen()) { + if (!_engine) return false; + const AndroidSerial::SerialParameters params{ + .baudRate = baudRate, + .dataBits = static_cast(dataBits), + .stopBits = static_cast(stopBits), + .parity = parityToWire(parity), + }; + if (!_engine->setParameters(params)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set serial parameters")); + return false; + } + } + _baudRate = baudRate; + _dataBits = dataBits; + _stopBits = stopBits; + _parity = parity; + if (baudDiff) emit baudRateChanged(baudRate); + if (dataDiff) emit dataBitsChanged(dataBits); + if (stopDiff) emit stopBitsChanged(stopBits); + if (parityDiff) emit parityChanged(parity); + return true; +} + +bool QGCAndroidSerialPort::setFlowControl(QGCFlowControl flowControl) +{ + if (_flowControl == flowControl) return true; + if (isOpen()) { + if (!_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Failed to set flow control")); + return false; + } + if (!_engine->setFlowControl(flowControlToWire(flowControl))) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set flow control")); + return false; + } + } + _flowControl = flowControl; + emit flowControlChanged(flowControl); + return true; +} + +// ============================================================================ +// Control lines +// ============================================================================ + +bool QGCAndroidSerialPort::setDataTerminalReady(bool set) +{ + if (!isOpen() || !_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return false; + } + const bool prev = isDataTerminalReady(); + if (!_engine->setDataTerminalReady(set)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set DTR")); + return false; + } + if (prev != set) emit dataTerminalReadyChanged(set); + return true; +} + +bool QGCAndroidSerialPort::setRequestToSend(bool set) +{ + if (!isOpen() || !_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return false; + } + if (_flowControl == QGCFlowControl::HardwareRtsCts) { + _setError(QGCSerialPortError::UnsupportedOperation, + tr("RTS cannot be set when hardware flow control is enabled")); + return false; + } + const bool prev = isRequestToSend(); + if (!_engine->setRequestToSend(set)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set RTS")); + return false; + } + if (prev != set) emit requestToSendChanged(set); + return true; +} + +bool QGCAndroidSerialPort::isDataTerminalReady() +{ + return pinoutSignals() & QGCPinoutSignals::DTR; +} + +bool QGCAndroidSerialPort::isRequestToSend() +{ + return pinoutSignals() & QGCPinoutSignals::RTS; +} + +quint32 QGCAndroidSerialPort::pinoutSignals() +{ + if (!isOpen() || !_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return QGCPinoutSignals::None; + } + return _engine->controlLinesMask(); +} + +bool QGCAndroidSerialPort::setBreakEnabled(bool set) +{ + if (!isOpen() || !_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return false; + } + if (!_engine->setBreak(set)) { + _setError(QGCSerialPortError::UnsupportedOperation, tr("Failed to set Break enabled")); + return false; + } + if (_breakEnabled != set) { + _breakEnabled = set; + emit breakEnabledChanged(set); + } + return true; +} + +bool QGCAndroidSerialPort::sendBreak(int duration) +{ + Q_UNUSED(duration); + // Timed break is not supported over Android USB host API. setBreakEnabled(true/false) + // is available for untimed break. + return false; +} + +bool QGCAndroidSerialPort::flush() +{ + if (!isOpen()) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return false; + } + // Non-blocking, matching upstream Qt serial backends — drains via the same async path + // used after writeData(). Callers needing to block must use waitForBytesWritten(). + _drainWriteBuffer(); + return _writeBuffer.isEmpty(); +} + +bool QGCAndroidSerialPort::clear(bool input, bool output) +{ + if (!isOpen() || !_engine) { + _setError(QGCSerialPortError::NotOpen, tr("Device is not open")); + return false; + } + if (input) { + _readBuffer.clear(); + _readOffset = 0; + _engine->clearReadStaging(); + } + if (output) { + _writeBuffer.clear(); + } + if (!_engine->purgeBuffers(input, output)) { + _setError(QGCSerialPortError::Unknown, tr("Failed to purge buffers")); + return false; + } + return true; +} + +// ============================================================================ +// Error reporting +// ============================================================================ + +void QGCAndroidSerialPort::_setError(QGCSerialPortError errorCode, const QString& errorString) +{ + _error = errorCode; + if (!errorString.isEmpty()) { + setErrorString(errorString); + } + emit errorOccurred(errorCode); +} + +void QGCAndroidSerialPort::clearError() +{ + _error = QGCSerialPortError::NoError; + setErrorString({}); +} diff --git a/src/Android/qtandroidserialport/QGCAndroidSerialPort.h b/src/Android/qtandroidserialport/QGCAndroidSerialPort.h new file mode 100644 index 000000000000..a28dc19b9083 --- /dev/null +++ b/src/Android/qtandroidserialport/QGCAndroidSerialPort.h @@ -0,0 +1,280 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#pragma once + +// +// QGCAndroidSerialPort +// +// Sibling QIODevice that replaces QGC's QSerialPortPrivate override on Android. +// +// Background. Until task fix/android-serial-overhaul, QGC shipped a custom +// QSerialPortPrivate that shadowed Qt's private API (``, +// `Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS`, etc.) and forced an Android-only divergence +// in SerialLink.h via `#ifdef Q_OS_ANDROID #include "qserialport.h"`. That design: +// (1) silently breaks on every Qt minor bump that touches QSerialPort internals, +// (2) blocks host-side testing — Qt's QtSerialPort module already provides +// QSerialPort + private impl on host, so linking our copy collides, +// (3) forces every consumer to think in QSerialPort::Foo enums even on Android +// where the underlying engine is JNI-backed and has no termios semantics. +// +// This class replaces that pattern. It is a regular QIODevice subclass owned by +// SerialLink (via QGCSerialPortFactory), with its own writeBuffer / readBuffer / +// error state / configuration getters. Zero dependency on Qt-private headers. +// +// Construction lifecycle: +// 1. SerialLink (or its worker) instantiates QGCAndroidSerialPort. +// 2. Caller wires Q_PROPERTY-equivalent setters (setBaudRate, setDataBits, ...) +// while state == Closed. Setters cache to local fields; no engine call yet. +// 3. Caller invokes open(QIODevice::ReadWrite). open() constructs the engine +// via QGCAndroidSerialPortFactory::createEngine() (default: QAndroidSerialEngine; +// tests inject MockQSerialPortEngine), pushes cached config to the engine, and +// starts the read thread. +// 4. Engine callbacks (dataReady / closeNotification / exceptionNotification) +// are received via the inherited QAndroidSerialEngineReceiver interface and +// marshaled to the owner thread before reaching this object. +// 5. close() emits aboutToClose() *first* (matches QIODevice contract — fixes +// the inversion noted by qt-qml-expert finding #4 in fix/android-serial-overhaul), +// then tears down the engine, then emits readChannelFinished(). +// +// Migration plan (multi-session): +// - Session 1: this header (API contract). +// - Session 2: implementation that wraps existing QAndroidSerialEngine + reuses +// the writeBuffer drain / _expectClosure / re-entrancy guard logic +// lifted verbatim from QSerialPortPrivate. +// - Session 3: QGCSerialPortFactory + SerialLink polymorphism (replace the +// `#ifdef Q_OS_ANDROID` in SerialLink.h with runtime dispatch). +// - Session 4: migrate QGCSerialPortInfo Android path to enumerate this type. +// - Session 5: host-side QGCAndroidSerialPortTest exercising the production +// logic via injected MockQSerialPortEngine (task #1, was task #2). +// - Session 6+: delete src/Android/qtandroidserialport/qserialport*.* and the +// `#ifdef Q_OS_ANDROID` branches in consumers. +// + +#include +#include +#include +#include + +#include +#include + +#include "AndroidSerial.h" +#include "iqserialportengine_p.h" +#include "qandroidserialenginereceiver_p.h" + +QT_FORWARD_DECLARE_CLASS(QObject) + +// Error classification. Intentionally NOT QSerialPort::SerialPortError — we don't want +// to leak QtSerialPort enums into a class that has no termios concept. Translation to +// QSerialPort errors (if SerialLink chooses to expose them) happens at the boundary. +enum class QGCSerialPortError { + NoError, + NotOpen, + OpenFailed, + PermissionDenied, // USB permission denied or device in use + ResourceUnavailable, // Device disappeared (cable yanked, runner stopped) + Read, + Write, + Timeout, + UnsupportedOperation, + Unknown, +}; + +// Data bits / parity / stop bits / flow control — own enums, not QSerialPort::*. +// Values match standard wire encodings so engine impls don't need translation tables. +enum class QGCDataBits : uint8_t { Data5 = 5, Data6 = 6, Data7 = 7, Data8 = 8 }; +enum class QGCParity : uint8_t { None = 0, Odd = 1, Even = 2, Mark = 3, Space = 4 }; +enum class QGCStopBits : uint8_t { One = 1, OneAndHalf = 3, Two = 2 }; + +enum class QGCFlowControl : uint8_t { + None = 0, + HardwareRtsCts = 1, + SoftwareXonXoff = 2, +}; + +// Pinout signal bitmask. Matches QSerialPort::PinoutSignals values exactly so the +// SerialLink-layer translation is a static_cast, not a switch. +struct QGCPinoutSignals +{ + enum Signal : quint32 { + None = 0x000, + TxD = 0x001, + RxD = 0x002, + DTR = 0x004, + DSR = 0x008, + DCD = 0x010, + RNG = 0x020, + RTS = 0x040, + CTS = 0x080, + SecTxD = 0x100, + SecRxD = 0x200, + }; +}; + +// Process-wide engine factory. Defaults to QAndroidSerialEngine. Tests can swap to +// MockQSerialPortEngine via setEngineFactory(). Mirrors QSerialPortPrivate::EngineFactory +// from the legacy implementation — kept here so the public-facing class owns it. +class QGCAndroidSerialPortFactory +{ +public: + using EngineFactory = std::function( + QAndroidSerialEngineReceiver*, QObject*)>; + + // Setter is process-wide and NOT thread-safe. Call from test setup before + // constructing any QGCAndroidSerialPort instance. + static void setEngineFactory(EngineFactory factory); + static void resetEngineFactory(); // Restore default (QAndroidSerialEngine). + +private: + friend class QGCAndroidSerialPort; + static EngineFactory& _engineFactory(); +}; + +// QIODevice replacement for QSerialPort on Android. No Qt-private dependencies. +class QGCAndroidSerialPort : public QIODevice, private QAndroidSerialEngineReceiver +{ + Q_OBJECT + +public: + explicit QGCAndroidSerialPort(QObject* parent = nullptr); + explicit QGCAndroidSerialPort(const QString& systemLocation, QObject* parent = nullptr); + ~QGCAndroidSerialPort() override; + + // --- QIODevice --- + bool isSequential() const override { return true; } + bool open(QIODeviceBase::OpenMode mode) override; + void close() override; + qint64 bytesAvailable() const override; + qint64 bytesToWrite() const override; + bool canReadLine() const override; + bool waitForReadyRead(int msecs) override; + bool waitForBytesWritten(int msecs) override; + + // --- Port identification --- + QString systemLocation() const { return _systemLocation; } + void setSystemLocation(const QString& location); + QString portName() const; // Display name (last path component). + + // --- Configuration (callable while open or closed) --- + // Closed: cached for the next open(). Open: applied immediately, returns false + // on engine rejection. + bool setBaudRate(qint32 baudRate); + qint32 baudRate() const { return _baudRate; } + + bool setDataBits(QGCDataBits dataBits); + QGCDataBits dataBits() const { return _dataBits; } + + bool setParity(QGCParity parity); + QGCParity parity() const { return _parity; } + + bool setStopBits(QGCStopBits stopBits); + QGCStopBits stopBits() const { return _stopBits; } + + // Batched parameter setter — collapses what would otherwise be four + // sequential setSerialParameters JNI calls (one per setter) into one. + // Emits only the *Changed signals whose values actually moved. + bool setSerialParameters(qint32 baudRate, QGCDataBits dataBits, + QGCStopBits stopBits, QGCParity parity); + + bool setFlowControl(QGCFlowControl flowControl); + QGCFlowControl flowControl() const { return _flowControl; } + + // --- Control lines (open only) --- + bool setDataTerminalReady(bool set); + bool setRequestToSend(bool set); + bool isDataTerminalReady(); + bool isRequestToSend(); + quint32 pinoutSignals(); // Bitmask of QGCPinoutSignals::Signal values. + + bool setBreakEnabled(bool set); + bool isBreakEnabled() const { return _breakEnabled; } + bool sendBreak(int duration); + + bool flush(); + bool clear(bool input = true, bool output = true); + + // --- Error reporting --- + QGCSerialPortError error() const { return _error; } + void clearError(); + + // --- Buffer sizing --- + qint64 readBufferSize() const { return _readBufferMaxSize; } + void setReadBufferSize(qint64 size); + qint64 writeBufferSize() const { return _writeBufferMaxSize; } + void setWriteBufferSize(qint64 size); + +signals: + void errorOccurred(QGCSerialPortError error); + void baudRateChanged(qint32 baudRate); + void dataBitsChanged(QGCDataBits dataBits); + void parityChanged(QGCParity parity); + void stopBitsChanged(QGCStopBits stopBits); + void flowControlChanged(QGCFlowControl flowControl); + void breakEnabledChanged(bool set); + void dataTerminalReadyChanged(bool set); + void requestToSendChanged(bool set); + +protected: + // --- QIODevice --- + qint64 readData(char* data, qint64 maxSize) override; + qint64 readLineData(char* data, qint64 maxSize) override; + qint64 writeData(const char* data, qint64 maxSize) override; + + // --- QAndroidSerialEngineReceiver --- + // Engine has already marshaled these to the owner thread before invoking. + void dataReady(QByteArray&& bytes) override; + void closeNotification() override; + void exceptionNotification(AndroidSerial::JavaExceptionKind kind, const QString& message) override; + +private: + void _setError(QGCSerialPortError errorCode, const QString& errorString = {}); + bool _startAsyncRead(); + bool _stopAsyncRead(); + void _drainWriteBuffer(); + qint64 _writeToEngine(const char* data, qint64 maxSize, int timeout, bool async); + + // Engine instance. Created in open(), reset in close(). Typed as the interface + // so the factory can return MockQSerialPortEngine for tests. + std::unique_ptr _engine; + + // Owner-thread write-buffer drain. Created in open(), reset in close(). + // QChronoTimer is thread-affine; start() from a foreign thread is not safe. + std::unique_ptr _writeTimer; + + // Internal buffers (no QIODevicePrivate dependency). + // + // _readOffset is QIODevicePrivate's trick (see qiodevice_p.h): consume from the + // front by bumping the offset, only memmove-compact when the dead prefix is large. + // Avoids the O(n) QByteArray::remove(0, n) on every readData() at high baud. + QByteArray _readBuffer; + qsizetype _readOffset = 0; + QByteArray _writeBuffer; + qint64 _readBufferMaxSize = 0; + qint64 _writeBufferMaxSize = 0; + + // Cached configuration. Pushed to engine in open(); also applied via setters + // while open. + QString _systemLocation; + qint32 _baudRate = 57600; + QGCDataBits _dataBits = QGCDataBits::Data8; + QGCParity _parity = QGCParity::None; + QGCStopBits _stopBits = QGCStopBits::One; + QGCFlowControl _flowControl = QGCFlowControl::None; + bool _breakEnabled = false; + + // Error state (mirrors QSerialPort::SerialPortError pattern but native enum). + QGCSerialPortError _error = QGCSerialPortError::NoError; + + // Re-entrancy guards. Mirrors Qt upstream qserialport_unix.cpp pattern: a slot + // connected to readyRead() may call write() which schedules a drain; without + // these flags a slot connected to bytesWritten() that calls readAll() (or + // vice versa) can recurse. Reset in close() so reopen doesn't swallow the + // first emit. + bool _emittedReadyRead = false; + bool _emittedBytesWritten = false; + + // Pre-close flag. Mirrors Qt BluetoothSocket InputStreamThread::expectClosure: + // set before tearing down _engine so the racing Java IOException from the + // forced close is reported as expected, not as ResourceUnavailable. + bool _expectClosure = false; +}; diff --git a/src/Android/qtandroidserialport/iqserialportengine_p.h b/src/Android/qtandroidserialport/iqserialportengine_p.h new file mode 100644 index 000000000000..960ac11be2b1 --- /dev/null +++ b/src/Android/qtandroidserialport/iqserialportengine_p.h @@ -0,0 +1,69 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +// +// W A R N I N G +// ------------- +// +// This file is not part of the Qt API. It exists purely as an implementation +// detail of QGC's Android QSerialPort backend. +// + +#include +#include +#include +#include + +#include "AndroidSerial.h" + +// Abstract engine surface consumed by QSerialPortPrivate. Decouples the Qt-side QIODevice +// implementation from the JNI-backed concrete engine (QAndroidSerialEngine), so a host-side +// mock (MockQSerialPortEngine) can implement the same contract without JNI dependencies. +// +// Receiver callbacks (data/close/exception) live on QAndroidSerialEngineReceiver — kept +// separate so the engine can call back into QSerialPortPrivate without circular includes. +class IQSerialPortEngine +{ +public: + enum class State { Closed, Opening, Open, Closing }; + + virtual ~IQSerialPortEngine() = default; + + // --- Lifecycle --- + [[nodiscard]] virtual bool open(const QString& portName, + const AndroidSerial::SerialParameters& params, + int flowControl, bool assertDtr) = 0; + virtual void close() = 0; + virtual bool isOpen() const = 0; + virtual State state() const = 0; + virtual int deviceHandle() const = 0; + + // --- Configuration --- + [[nodiscard]] virtual bool setParameters(const AndroidSerial::SerialParameters& p) = 0; + [[nodiscard]] virtual bool setDataTerminalReady(bool set) = 0; + [[nodiscard]] virtual bool setRequestToSend(bool set) = 0; + [[nodiscard]] virtual bool setFlowControl(int flowControl) = 0; + virtual int flowControl() const = 0; + [[nodiscard]] virtual bool setBreak(bool set) = 0; + [[nodiscard]] virtual bool purgeBuffers(bool input, bool output) = 0; + + // Bitmask of QSerialPort::PinoutSignal values. Returned as quint32 so this interface + // header doesn't have to drag in the platform-specific QSerialPort header — the + // QSerialPortPrivate consumer casts back to QSerialPort::PinoutSignals at the boundary. + virtual quint32 controlLinesMask() const = 0; + + // --- I/O --- + virtual int writeSync(QSpan data, int timeout) = 0; + virtual int writeAsync(QSpan data, int timeout) = 0; + + // --- Read thread --- + [[nodiscard]] virtual bool startReadThread() = 0; + [[nodiscard]] virtual bool stopReadThread() = 0; + virtual bool readThreadRunning() const = 0; + + // --- Read staging --- + virtual void setReadBufferMaxSize(qint64 bytes) = 0; + virtual void clearReadStaging() = 0; + virtual QByteArray waitForReadyRead(int msecs, qint64 ownerBufferSize) = 0; +}; diff --git a/src/Android/qtandroidserialport/qandroidserialengine.cpp b/src/Android/qtandroidserialport/qandroidserialengine.cpp new file mode 100644 index 000000000000..2b18c967aa1b --- /dev/null +++ b/src/Android/qtandroidserialport/qandroidserialengine.cpp @@ -0,0 +1,643 @@ +#include "qandroidserialengine_p.h" +#include "QGCAndroidSerialPort.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "qandroidserialenginereceiver_p.h" +#include "QGCLoggingCategory.h" + +#include + +Q_DECLARE_JNI_CLASS(QGCUsbSerialManager, "org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager") +Q_DECLARE_JNI_CLASS(QGCUsbSerialManagerSerialParameters, + "org/mavlink/qgroundcontrol/serial/QGCUsbSerialManager$SerialParameters") + +QGC_LOGGING_CATEGORY(AndroidSerialEngineLog, "Android.Serial.Engine"); +QGC_LOGGING_CATEGORY(AndroidSerialEngineVerboseLog, "Android.Serial.Engine:verbose"); + +namespace { +QtJniTypes::QGCUsbSerialManagerSerialParameters makeSerialParamsJni(const AndroidSerial::SerialParameters& p) +{ + return QJniObject::construct( + static_cast(p.baudRate), static_cast(p.dataBits), + static_cast(p.stopBits), static_cast(p.parity)); +} +} // namespace + +// ---------------------------------------------------------------------------- +// JNI call helpers — collapse the per-method state-check / call / exception-check +// boilerplate that otherwise repeats verbatim across ~15 methods. +// ---------------------------------------------------------------------------- + +namespace { + +// Calls QGCUsbSerialManager.(deviceId, args...) and returns the result, or `onError` +// if the JNI call threw. Centralizes the exception-check + warning log path. +// +// Hot-path note: uses the static QJniEnvironment::getJniEnv()+checkAndClearExceptions(JNIEnv*) pair +// rather than constructing a QJniEnvironment{}. On an already-attached thread that's a single +// JavaVM::GetEnv() TLS read instead of a QJniEnvironment object construction; matters because +// this helper runs on every writeSync/writeAsync per MAVLink packet. +template +Ret callJniDevice(const char* method, int deviceId, Ret onError, Args&&... args) +{ + const Ret r = QJniObject::callStaticMethod( + method, static_cast(deviceId), std::forward(args)...); + if (QJniEnvironment::checkAndClearExceptions(QJniEnvironment::getJniEnv(), + QJniEnvironment::OutputMode::Silent)) { + qCWarning(AndroidSerialEngineLog) << "JNI exception in" << method << "for device ID" << deviceId; + return onError; + } + return r; +} + +} // anonymous namespace + +// ---------------------------------------------------------------------------- +// Token registry (file-scope statics) +// +// Maps the opaque jlong token Java holds → the live QAndroidSerialEngine that owns the +// JNI bridge. Java never sees a raw C++ pointer; on stale tokens (engine destroyed +// between the Java IO thread fetching the token and calling back) the lookup returns +// null and the callback is a no-op. Mirrors the Qt Bluetooth LowEnergyNotificationHub +// pattern for the same reason: usb-serial-for-android's IO thread join is best-effort +// (2 s polling timeout), so the callback path must tolerate races. +// ---------------------------------------------------------------------------- + +static QReadWriteLock s_ptrLock; +static QHash s_tokenToEngine; +static QHash s_engineToToken; + +// ---------------------------------------------------------------------------- +// JNI callbacks (called from Java IO threads — class statics, registered below) +// ---------------------------------------------------------------------------- + +void QAndroidSerialEngine::jniDeviceHasDisconnected(JNIEnv*, jobject, jlong token) +{ + if (token == 0) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceHasDisconnected called with token=0"; + return; + } + + // Engine internally marshals to its owner thread; we only need to keep the engine alive + // across the synchronous dispatch call. + QReadLocker locker(&s_ptrLock); + QAndroidSerialEngine* const engine = s_tokenToEngine.value(token, nullptr); + if (!engine) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceHasDisconnected: stale token, engine already destroyed"; + return; + } + engine->dispatchCloseFromJavaThread(); +} + +void QAndroidSerialEngine::jniDeviceNewData(JNIEnv* env, jobject, jlong token, + QtJniTypes::ByteBuffer buffer, jint length) +{ + // Java passes a direct ByteBuffer; GetDirectBufferAddress returns a raw pointer + // to it with no extra copy at this boundary. The Java-side memcpy (upstream + // byte[] → direct buffer) is unavoidable without patching usb-serial-for-android. + + constexpr jsize kMaxNativePayloadBytes = static_cast(AndroidSerial::MAX_READ_SIZE); + + if (token == 0) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceNewData called with token=0"; + return; + } + + if (!buffer.isValid()) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceNewData called with null buffer"; + return; + } + + if (length <= 0) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceNewData received empty data (length=" << length << ")"; + return; + } + + void* const ptr = env->GetDirectBufferAddress(buffer.object()); + if (!ptr) { + qCWarning(AndroidSerialEngineLog) + << "nativeDeviceNewData: GetDirectBufferAddress returned null — buffer is not direct"; + return; + } + + // Use the caller-supplied length, not GetDirectBufferCapacity: pooled buffers + // are allocated at MAX_NATIVE_CALLBACK_DATA_BYTES capacity but may carry fewer + // valid bytes than their capacity when the payload is smaller. + const jsize cappedLen = (length > kMaxNativePayloadBytes) ? kMaxNativePayloadBytes : static_cast(length); + if (cappedLen != static_cast(length)) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceNewData payload exceeds limit, truncating from" + << length << "to" << cappedLen << "bytes"; + } + + // QByteArray(ptr, n) copies the bytes into Qt-managed heap. This copy is required + // because the direct buffer is returned to Java's pool immediately after this JNI + // call returns — we cannot use QByteArray::fromRawData without blocking Java until + // the Qt dispatch fully consumes the data. + const QByteArray payload(reinterpret_cast(ptr), static_cast(cappedLen)); + + // Hold s_ptrLock(read) across enqueueFromJavaThread to block _unregisterToken (write lock) + // until this callback returns. Lock order: s_ptrLock(read) → engine._readMutex. The + // engine's owner-thread close() does not take _readMutex before _unregisterToken, so no + // inversion. + QReadLocker locker(&s_ptrLock); + QAndroidSerialEngine* const engine = s_tokenToEngine.value(token, nullptr); + if (!engine) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceNewData: stale token, engine already destroyed"; + return; + } + + if (AndroidSerialEngineVerboseLog().isDebugEnabled()) { + const auto firstByte = static_cast(static_cast(payload.at(0))); + qCDebug(AndroidSerialEngineVerboseLog).nospace().noquote() + << "nativeDeviceNewData token=" << token + << " n=" << payload.size() + << " first=0x" << QString::asprintf("%02x", firstByte); + } + + engine->enqueueFromJavaThread(payload); +} + +void QAndroidSerialEngine::jniDeviceException(JNIEnv* env, jobject, jlong token, jint kind, jstring message) +{ + if (token == 0) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceException called with token=0"; + return; + } + + if (!message) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceException called with null message"; + return; + } + + const QString exceptionMessage = QJniObject(message).toString(); + if (QJniEnvironment::checkAndClearExceptions(env, QJniEnvironment::OutputMode::Silent)) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceException: exception converting jstring"; + } + + // Out-of-range kind values fall back to Unknown rather than UB on the cast. + const auto kindEnum = (kind >= 0 && kind <= static_cast(AndroidSerial::JavaExceptionKind::OpenFailed)) + ? static_cast(kind) + : AndroidSerial::JavaExceptionKind::Unknown; + + QReadLocker locker(&s_ptrLock); + QAndroidSerialEngine* const engine = s_tokenToEngine.value(token, nullptr); + if (!engine) { + qCWarning(AndroidSerialEngineLog) << "nativeDeviceException: stale token, engine already destroyed"; + return; + } + + qCWarning(AndroidSerialEngineLog) << "Exception from Java:" << exceptionMessage << "kind=" << kind; + engine->dispatchExceptionFromJavaThread(kindEnum, exceptionMessage); +} + +// ---------------------------------------------------------------------------- +// QAndroidSerialEngine implementation +// ---------------------------------------------------------------------------- + +QAndroidSerialEngine::QAndroidSerialEngine(QAndroidSerialEngineReceiver* sink, QObject* owner) + : _sink(sink), _owner(owner) +{ +} + +QAndroidSerialEngine::~QAndroidSerialEngine() +{ + if (_state != State::Closed) { + close(); + } + _unregisterToken(); +} + +void QAndroidSerialEngine::_registerToken() +{ + QWriteLocker locker(&s_ptrLock); + + const auto existingIt = s_engineToToken.constFind(this); + if (existingIt != s_engineToToken.cend()) { + s_tokenToEngine.remove(*existingIt); + s_engineToToken.erase(existingIt); + } + + // Random non-zero token, retry on collision (mirrors Qt BLE LowEnergyNotificationHub). + // Opacity over a monotonic counter: a misbehaving .apk can't infer engine lifetime/order + // from sequential IDs. token=0 stays reserved as the JNI "no token" sentinel. + jlong token = 0; + while (token == 0 || s_tokenToEngine.contains(token)) { + token = static_cast(QRandomGenerator::global()->generate64()); + } + + s_tokenToEngine.insert(token, this); + s_engineToToken.insert(this, token); + _token = token; +} + +void QAndroidSerialEngine::_unregisterToken() +{ + if (_token == 0) { + return; + } + + QWriteLocker locker(&s_ptrLock); + s_engineToToken.remove(this); + s_tokenToEngine.remove(_token); + _token = 0; +} + +bool QAndroidSerialEngine::open(const QString& portName, const AndroidSerial::SerialParameters& params, + int flowControl, bool assertDtr) +{ + if (_state != State::Closed) { + qCWarning(AndroidSerialEngineLog) << "open called on non-closed port, device ID" << _deviceId; + return false; + } + + _state = State::Opening; + + _registerToken(); + if (_token == 0) { + qCWarning(AndroidSerialEngineLog) << "open: failed to register token for" << portName; + _state = State::Closed; + return false; + } + + const QJniObject name = QJniObject::fromString(portName); + if (!name.isValid()) { + qCWarning(AndroidSerialEngineLog) << "Invalid QJniObject for portName in open"; + _unregisterToken(); + _state = State::Closed; + return false; + } + + const auto paramsObj = makeSerialParamsJni(params); + if (!paramsObj.isValid()) { + qCWarning(AndroidSerialEngineLog) << "Failed to construct SerialParameters JNI object"; + _unregisterToken(); + _state = State::Closed; + return false; + } + + const jint deviceId = QJniObject::callStaticMethod( + "openWithConfig", name.object(), paramsObj, + static_cast(flowControl), static_cast(assertDtr), _token); + if (QJniEnvironment::checkAndClearExceptions(QJniEnvironment::getJniEnv(), + QJniEnvironment::OutputMode::Silent)) { + qCWarning(AndroidSerialEngineLog) << "Exception in openWithConfig for" << portName; + _unregisterToken(); + _state = State::Closed; + return false; + } + + if (static_cast(deviceId) == AndroidSerial::INVALID_DEVICE_ID) { + qCWarning(AndroidSerialEngineLog) << "openWithConfig returned INVALID_DEVICE_ID for" << portName; + _unregisterToken(); + _state = State::Closed; + return false; + } + + _deviceId = static_cast(deviceId); + _state = State::Open; + return true; +} + +void QAndroidSerialEngine::close() +{ + if (_state == State::Closed) { + return; + } + + // Mute the IO thread before invalidating the token. Java's close also stops the IO + // manager, but ordering it here means a Java callback racing the JNI close still + // resolves the token while the engine is alive (s_ptrLock guards the dispatch). + if (_deviceId != AndroidSerial::INVALID_DEVICE_ID && _state == State::Open) { + callJniDevice("stopIoManager", _deviceId, JNI_FALSE); + } + + _state = State::Closing; + + if (_deviceId != AndroidSerial::INVALID_DEVICE_ID) { + if (!callJniDevice("close", _deviceId, JNI_FALSE)) { + qCWarning(AndroidSerialEngineLog) << "close returned false for device ID" << _deviceId; + } + _deviceId = AndroidSerial::INVALID_DEVICE_ID; + } + + _unregisterToken(); + _state = State::Closed; + + // Wake any thread blocked in waitForReadyRead so it observes the closed state + // and exits the wait loop instead of timing out (or blocking forever on -1). + { + QMutexLocker locker(&_readMutex); + _readWaitCondition.wakeAll(); + } +} + +int QAndroidSerialEngine::deviceHandle() const +{ + if (_state != State::Open) return -1; + return callJniDevice("getDeviceHandle", _deviceId, -1); +} + +bool QAndroidSerialEngine::setParameters(const AndroidSerial::SerialParameters& p) +{ + if (_state != State::Open) return false; + + const auto paramsObj = makeSerialParamsJni(p); + if (!paramsObj.isValid()) { + qCWarning(AndroidSerialEngineLog) << "Failed to construct SerialParameters JNI object"; + return false; + } + + return callJniDevice("setSerialParameters", _deviceId, JNI_FALSE, paramsObj); +} + +bool QAndroidSerialEngine::setDataTerminalReady(bool set) +{ + if (_state != State::Open) return false; + return callJniDevice("setDataTerminalReady", _deviceId, JNI_FALSE, static_cast(set)); +} + +bool QAndroidSerialEngine::setRequestToSend(bool set) +{ + if (_state != State::Open) return false; + return callJniDevice("setRequestToSend", _deviceId, JNI_FALSE, static_cast(set)); +} + +quint32 QAndroidSerialEngine::controlLinesMask() const +{ + if (_state != State::Open) return 0u; + + const auto ints = callJniDevice>("getControlLines", _deviceId, QJniArray()); + if (!ints.isValid()) return 0u; + + quint32 data = 0; + for (const jint code : ints) { + switch (code) { + case AndroidSerial::RtsControlLine: data |= QGCPinoutSignals::RTS; break; + case AndroidSerial::CtsControlLine: data |= QGCPinoutSignals::CTS; break; + case AndroidSerial::DtrControlLine: data |= QGCPinoutSignals::DTR; break; + case AndroidSerial::DsrControlLine: data |= QGCPinoutSignals::DSR; break; + case AndroidSerial::CdControlLine: data |= QGCPinoutSignals::DCD; break; + case AndroidSerial::RiControlLine: data |= QGCPinoutSignals::RNG; break; + default: + qCWarning(AndroidSerialEngineLog) << "Unknown ControlLine value:" << code; + break; + } + } + + return data; +} + +int QAndroidSerialEngine::flowControl() const +{ + if (_state != State::Open) return AndroidSerial::NoFlowControl; + return callJniDevice("getFlowControl", _deviceId, AndroidSerial::NoFlowControl); +} + +bool QAndroidSerialEngine::setFlowControl(int fc) +{ + if (_state != State::Open) return false; + return callJniDevice("setFlowControl", _deviceId, JNI_FALSE, static_cast(fc)); +} + +bool QAndroidSerialEngine::purgeBuffers(bool input, bool output) +{ + if (_state != State::Open) return false; + return callJniDevice("purgeBuffers", _deviceId, JNI_FALSE, + static_cast(input), static_cast(output)); +} + +bool QAndroidSerialEngine::setBreak(bool set) +{ + if (_state != State::Open) return false; + return callJniDevice("setBreak", _deviceId, JNI_FALSE, static_cast(set)); +} + +int QAndroidSerialEngine::_write(const char* javaMethod, QSpan data, int timeout) +{ + if (_state != State::Open) return -1; + if (data.empty()) { + qCWarning(AndroidSerialEngineLog) << "Invalid data or length in" << javaMethod << "for device ID" << _deviceId; + return -1; + } + + // NewDirectByteBuffer wraps the C++-owned buffer without copying. Java still copies once + // (direct ByteBuffer → heap byte[]) because usb-serial-for-android's UsbSerialPort.write() + // takes byte[]. The eliminated copy is the old NewByteArray + SetByteArrayRegion path. + JNIEnv* const env = QJniEnvironment::getJniEnv(); + const jobject jBufferRaw = env->NewDirectByteBuffer(const_cast(data.data()), + static_cast(data.size())); + if (!jBufferRaw) { + qCWarning(AndroidSerialEngineLog) << "Failed to create DirectByteBuffer in" << javaMethod + << "for device ID" << _deviceId; + return -1; + } + const auto bufferGuard = qScopeGuard([&]{ env->DeleteLocalRef(jBufferRaw); }); + const QtJniTypes::ByteBuffer jBuffer{jBufferRaw}; + + const jint rc = callJniDevice(javaMethod, _deviceId, -1, jBuffer, + static_cast(data.size()), static_cast(timeout)); + if (AndroidSerialEngineVerboseLog().isDebugEnabled()) { + const auto firstByte = data.empty() ? 0u : static_cast(static_cast(data[0])); + qCDebug(AndroidSerialEngineVerboseLog).nospace().noquote() + << javaMethod << " deviceId=" << _deviceId + << " n=" << data.size() << " rc=" << rc + << " first=0x" << QString::asprintf("%02x", firstByte); + } + return rc; +} + +int QAndroidSerialEngine::writeAsync(QSpan data, int timeout) +{ + return _write("writeAsyncDirect", data, timeout); +} + +int QAndroidSerialEngine::writeSync(QSpan data, int timeout) +{ + return _write("writeDirect", data, timeout); +} + +bool QAndroidSerialEngine::startReadThread() +{ + if (_state != State::Open) return false; + return callJniDevice("startIoManager", _deviceId, JNI_FALSE); +} + +bool QAndroidSerialEngine::stopReadThread() +{ + if (_state != State::Open) return false; + return callJniDevice("stopIoManager", _deviceId, JNI_FALSE); +} + +bool QAndroidSerialEngine::readThreadRunning() const +{ + if (_state != State::Open) return false; + return callJniDevice("ioManagerRunning", _deviceId, JNI_FALSE); +} + +// ---------------------------------------------------------------------------- +// Read-side staging (engine-internal thread marshaling) +// ---------------------------------------------------------------------------- + +void QAndroidSerialEngine::enqueueFromJavaThread(QByteArrayView bytes) +{ + { + QMutexLocker locker(&_readMutex); + + qsizetype toAccept = bytes.size(); + if (_readBufferMaxSize > 0) { + const qint64 headroom = _readBufferMaxSize - _pendingData.size(); + toAccept = qMin(toAccept, qMax(0, headroom)); + } + + if (toAccept > 0) { + _pendingData.append(bytes.first(toAccept)); + _readWaitCondition.wakeAll(); + } + + if (toAccept < bytes.size()) { + qCWarning(AndroidSerialEngineLog) << "Read buffer full, dropped" << (bytes.size() - toAccept) << "bytes"; + } + + if (toAccept <= 0) { + return; + } + } + + _scheduleDrainOnOwnerThread(); +} + +void QAndroidSerialEngine::_scheduleDrainOnOwnerThread() +{ + if (_readyReadPending.exchange(true)) { + return; // Drain already scheduled. + } + + QPointer owner = _owner; + if (!owner) { + // Owner gone — nothing to deliver to. + _readyReadPending.store(false); + return; + } + + // Receiver = _drainSentinel (engine member). When the engine is destroyed, the sentinel's + // destruction cancels any not-yet-delivered queued events, so we never call + // _drainOnOwnerThread() on a dead `this`. + QMetaObject::invokeMethod(&_drainSentinel, [this]() { + _drainOnOwnerThread(); + }, Qt::QueuedConnection); +} + +void QAndroidSerialEngine::_drainOnOwnerThread() +{ + QByteArray pending; + { + QMutexLocker locker(&_readMutex); + if (_pendingData.isEmpty()) { + _readyReadPending.store(false); + return; + } + + pending.swap(_pendingData); + // Reset the pending flag under the lock so a concurrent enqueue either sees + // the flag false (and posts a fresh drain) or true (and trusts that this drain + // will see its data). Without this, lost-wakeup is possible. + _readyReadPending.store(false); + _readWaitCondition.wakeAll(); + } + + if (_sink && !pending.isEmpty()) { + _sink->dataReady(std::move(pending)); + } +} + +void QAndroidSerialEngine::clearReadStaging() +{ + QMutexLocker locker(&_readMutex); + _pendingData.clear(); +} + +QByteArray QAndroidSerialEngine::waitForReadyRead(int msecs, qint64 ownerBufferSize) +{ + QMutexLocker locker(&_readMutex); + if (_pendingData.isEmpty() && _state == State::Open) { + QDeadlineTimer deadline(msecs); + while (_pendingData.isEmpty() && _state == State::Open) { + if (!_readWaitCondition.wait(&_readMutex, deadline)) { + break; + } + } + } + + if (_pendingData.isEmpty()) { + return QByteArray(); + } + + QByteArray data; + if (_readBufferMaxSize <= 0) { + data.swap(_pendingData); + } else { + const qint64 canAccept = qMax(0, _readBufferMaxSize - ownerBufferSize); + if (canAccept <= 0) { + // Caller's buffer at capacity. Wake other waiters and let caller retry. + _readWaitCondition.wakeAll(); + return QByteArray(); + } + const qsizetype n = qMin(static_cast(canAccept), _pendingData.size()); + if (n >= _pendingData.size()) { + data.swap(_pendingData); + } else { + data = _pendingData.first(n); + _pendingData.remove(0, n); + } + } + return data; +} + +void QAndroidSerialEngine::dispatchCloseFromJavaThread() +{ + _postToOwner([](QAndroidSerialEngineReceiver* sink) { sink->closeNotification(); }); +} + +void QAndroidSerialEngine::dispatchExceptionFromJavaThread(AndroidSerial::JavaExceptionKind kind, + const QString& message) +{ + _postToOwner([kind, message](QAndroidSerialEngineReceiver* sink) { + sink->exceptionNotification(kind, message); + }); +} + +// ---------------------------------------------------------------------------- +// Static initialization +// ---------------------------------------------------------------------------- + +void QAndroidSerialEngine::initialize() +{ + // Function-local static + lambda: idempotent under repeat calls (mirrors Qt's + // androidconnectivitymanager.cpp registerNatives pattern). Safe even if invoked + // outside JNI_OnLoad (e.g. JNI unload+reload). + static const bool registered = []() { + QJniEnvironment env; + const bool ok = env.registerNativeMethods({ + Q_JNI_NATIVE_SCOPED_METHOD(jniDeviceHasDisconnected, QAndroidSerialEngine), + Q_JNI_NATIVE_SCOPED_METHOD(jniDeviceNewData, QAndroidSerialEngine), + Q_JNI_NATIVE_SCOPED_METHOD(jniDeviceException, QAndroidSerialEngine), + }); + if (!ok) { + qCWarning(AndroidSerialEngineLog) << "Failed to register native methods for QGCUsbSerialManager"; + } else { + qCDebug(AndroidSerialEngineLog) << "Native Functions Registered Successfully"; + } + return ok; + }(); + Q_UNUSED(registered) +} diff --git a/src/Android/qtandroidserialport/qandroidserialengine_p.h b/src/Android/qtandroidserialport/qandroidserialengine_p.h new file mode 100644 index 000000000000..abe6e6e4319b --- /dev/null +++ b/src/Android/qtandroidserialport/qandroidserialengine_p.h @@ -0,0 +1,146 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "AndroidSerial.h" +#include "iqserialportengine_p.h" + +QT_BEGIN_NAMESPACE +class QObject; +class QString; +QT_END_NAMESPACE + +Q_DECLARE_JNI_CLASS(ByteBuffer, "java/nio/ByteBuffer") + +class QAndroidSerialEngineReceiver; + +// RAII per-port handle to the Android JNI USB serial bridge. +// +// Owns the staging buffer (_pendingData) and read-side thread marshaling. Bytes arrive on +// the Java IO thread, are appended to _pendingData under _readMutex, and are delivered to +// the receiver on the owner thread via QAndroidSerialEngineReceiver::dataReady. +class QAndroidSerialEngine : public IQSerialPortEngine +{ +public: + using State = IQSerialPortEngine::State; + + // owner: QObject whose thread should receive dataReady/closeNotification/ + // exceptionNotification (typically the QSerialPort). + QAndroidSerialEngine(QAndroidSerialEngineReceiver* sink, QObject* owner); + ~QAndroidSerialEngine() override; + + Q_DISABLE_COPY_MOVE(QAndroidSerialEngine) + + // Atomic open: applies parameters + flow control + DTR in a single JNI roundtrip. + // On failure the Java side has already cleaned up — no separate close() is needed. + [[nodiscard]] bool open(const QString& portName, const AndroidSerial::SerialParameters& params, + int flowControl, bool assertDtr) override; + void close() override; + bool isOpen() const override { return _state == State::Open; } + State state() const override { return _state; } + + int deviceHandle() const override; + + [[nodiscard]] bool setParameters(const AndroidSerial::SerialParameters& p) override; + [[nodiscard]] bool setDataTerminalReady(bool set) override; + [[nodiscard]] bool setRequestToSend(bool set) override; + [[nodiscard]] bool setFlowControl(int flowControl) override; + int flowControl() const override; + [[nodiscard]] bool setBreak(bool set) override; + [[nodiscard]] bool purgeBuffers(bool input, bool output) override; + + quint32 controlLinesMask() const override; + + int writeSync(QSpan data, int timeout) override; + int writeAsync(QSpan data, int timeout) override; + + [[nodiscard]] bool startReadThread() override; + [[nodiscard]] bool stopReadThread() override; + bool readThreadRunning() const override; + + // -- Read-side machinery (was on QSerialPortPrivate) ---------------------- + + // Mirror of QSerialPort::readBufferSize policy. 0 = unlimited. + void setReadBufferMaxSize(qint64 bytes) override { _readBufferMaxSize = bytes; } + + // Drops any staged bytes that haven't been delivered yet. Called from QSerialPort::clear. + void clearReadStaging() override; + + // Owner-thread blocking wait. Returns the staged bytes or empty on timeout. + // ownerBufferSize is the current QIODevice buffer size, used to enforce the read cap. + QByteArray waitForReadyRead(int msecs, qint64 ownerBufferSize) override; + + static void initialize(); + +private: + // -- JNI native callbacks (registered on QGCUsbSerialManager) --------------- + // Static so JNI can register them; class-scoped so they can't collide with + // free-function natives in other TUs. Resolve token→engine under s_ptrLock(read). + static void jniDeviceHasDisconnected(JNIEnv* env, jobject obj, jlong token); + static void jniDeviceNewData(JNIEnv* env, jobject obj, jlong token, + QtJniTypes::ByteBuffer buffer, jint length); + static void jniDeviceException(JNIEnv* env, jobject obj, jlong token, jint kind, jstring message); + + Q_DECLARE_JNI_NATIVE_METHOD_IN_CURRENT_SCOPE(jniDeviceHasDisconnected, nativeDeviceHasDisconnected) + Q_DECLARE_JNI_NATIVE_METHOD_IN_CURRENT_SCOPE(jniDeviceNewData, nativeDeviceNewData) + Q_DECLARE_JNI_NATIVE_METHOD_IN_CURRENT_SCOPE(jniDeviceException, nativeDeviceException) + + // -- JNI-thread dispatch entry points (called only by jni* statics above) --- + // Marshal to the owner thread before invoking the receiver. + void enqueueFromJavaThread(QByteArrayView bytes); + void dispatchCloseFromJavaThread(); + void dispatchExceptionFromJavaThread(AndroidSerial::JavaExceptionKind kind, const QString& message); + + QAndroidSerialEngineReceiver* _sink; + QPointer _owner; + int _deviceId = AndroidSerial::INVALID_DEVICE_ID; + jlong _token = 0; + // Atomic so cross-thread readers (notably waitForReadyRead) observe close() + // transitions without a data race. + std::atomic _state{State::Closed}; + + // Read staging — Java IO thread appends, owner thread drains. + qint64 _readBufferMaxSize = 0; + std::atomic _readyReadPending{false}; + QMutex _readMutex; + QWaitCondition _readWaitCondition; + QByteArray _pendingData; + + // Sentinel for queued drain events. Declared LAST so it is destroyed FIRST: that removes + // any pending _drainOnOwnerThread invocations from the owner's event queue before + // _readMutex/_readWaitCondition go away. Without this, a late-delivered drain would + // wakeAll() on a destroyed mutex (FORTIFY pthread abort). + QObject _drainSentinel; + + void _registerToken(); + void _unregisterToken(); + int _write(const char* javaMethod, QSpan data, int timeout); + void _scheduleDrainOnOwnerThread(); + void _drainOnOwnerThread(); + + // Posts `f(sink)` to the owner thread via QueuedConnection. No-op if owner or sink is null. + template + void _postToOwner(F&& f) + { + QPointer owner = _owner; + if (!owner || !_sink) return; + QAndroidSerialEngineReceiver* sink = _sink; + QMetaObject::invokeMethod(owner.data(), [owner, sink, f = std::forward(f)]() { + if (!owner) return; + f(sink); + }, Qt::QueuedConnection); + } +}; diff --git a/src/Android/qtandroidserialport/qandroidserialenginereceiver_p.h b/src/Android/qtandroidserialport/qandroidserialenginereceiver_p.h new file mode 100644 index 000000000000..57db925ed104 --- /dev/null +++ b/src/Android/qtandroidserialport/qandroidserialenginereceiver_p.h @@ -0,0 +1,28 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include +#include + +#include "AndroidSerial.h" + +QT_BEGIN_NAMESPACE +class QString; +QT_END_NAMESPACE + +// Mirrors QAbstractSocketEngineReceiver (qtbase/src/network/socket/qabstractsocketengine_p.h): +// abstract callback interface decoupling the JNI engine from the QIODevice receiver +// (QSerialPortPrivate). The engine owns thread marshaling internally — it stages bytes from +// the Java IO thread and delivers them on the owner thread via dataReady(). +class QAndroidSerialEngineReceiver +{ +public: + virtual ~QAndroidSerialEngineReceiver() = default; + + // All three callbacks run on the receiver's owner thread (the QSerialPort thread). + // dataReady carries already-staged bytes the engine has drained from its internal queue. + virtual void dataReady(QByteArray&& bytes) = 0; + virtual void closeNotification() = 0; + virtual void exceptionNotification(AndroidSerial::JavaExceptionKind kind, const QString& message) = 0; +}; diff --git a/src/Android/qtandroidserialport/qserialport.cpp b/src/Android/qtandroidserialport/qserialport.cpp deleted file mode 100644 index c5e14665ab17..000000000000 --- a/src/Android/qtandroidserialport/qserialport.cpp +++ /dev/null @@ -1,1209 +0,0 @@ -// Copyright (C) 2011-2012 Denis Shienkov -// Copyright (C) 2011 Sergey Belyashov -// Copyright (C) 2012 Laszlo Papp -// Copyright (C) 2012 Andre Hartmann -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#include "qserialport.h" - -#include - -#include "qserialport_p.h" -#include "qserialportinfo.h" -#include "qserialportinfo_p.h" - -QT_BEGIN_NAMESPACE - -QSerialPortErrorInfo::QSerialPortErrorInfo(QSerialPort::SerialPortError newErrorCode, const QString& newErrorString) - : errorCode(newErrorCode), errorString(newErrorString) -{ - if (errorString.isNull()) { - switch (errorCode) { - case QSerialPort::NoError: - errorString = QSerialPort::tr("No error"); - break; - case QSerialPort::OpenError: - errorString = QSerialPort::tr("Device is already open"); - break; - case QSerialPort::NotOpenError: - errorString = QSerialPort::tr("Device is not open"); - break; - case QSerialPort::TimeoutError: - errorString = QSerialPort::tr("Operation timed out"); - break; - case QSerialPort::ReadError: - errorString = QSerialPort::tr("Error reading from device"); - break; - case QSerialPort::WriteError: - errorString = QSerialPort::tr("Error writing to device"); - break; - case QSerialPort::ResourceError: - errorString = QSerialPort::tr("Device disappeared from the system"); - break; - default: - // an empty string will be interpreted as "Unknown error" - // from the QIODevice::errorString() - break; - } - } -} - -QSerialPortPrivate::QSerialPortPrivate() -{ - writeBufferChunkSize = QSERIALPORT_BUFFERSIZE; - readBufferChunkSize = QSERIALPORT_BUFFERSIZE; -} - -void QSerialPortPrivate::setError(const QSerialPortErrorInfo& errorInfo) -{ - Q_Q(QSerialPort); - - q->setErrorString(errorInfo.errorString); - error.setValue(errorInfo.errorCode); - error.notify(); - emit q->errorOccurred(error); -} - -/*! - \class QSerialPort - - \brief Provides functions to access serial ports. - - \reentrant - \ingroup serialport-main - \inmodule QtSerialPort - \since 5.1 - - You can get information about the available serial ports using the - QSerialPortInfo helper class, which allows an enumeration of all the serial - ports in the system. This is useful to obtain the correct name of the - serial port you want to use. You can pass an object - of the helper class as an argument to the setPort() or setPortName() - methods to assign the desired serial device. - - After setting the port, you can open it in read-only (r/o), write-only - (w/o), or read-write (r/w) mode using the open() method. - - \note The serial port is always opened with exclusive access - (that is, no other process or thread can access an already opened serial port). - - Use the close() method to close the port and cancel the I/O operations. - - Having successfully opened, QSerialPort tries to determine the current - configuration of the port and initializes itself. You can reconfigure the - port to the desired setting using the setBaudRate(), setDataBits(), - setParity(), setStopBits(), and setFlowControl() methods. - - There are a couple of properties to work with the pinout signals namely: - QSerialPort::dataTerminalReady, QSerialPort::requestToSend. It is also - possible to use the pinoutSignals() method to query the current pinout - signals set. - - Once you know that the ports are ready to read or write, you can - use the read() or write() methods. Alternatively the - readLine() and readAll() convenience methods can also be invoked. - If not all the data is read at once, the remaining data will - be available for later as new incoming data is appended to the - QSerialPort's internal read buffer. You can limit the size of the read - buffer using setReadBufferSize(). - - QSerialPort provides a set of functions that suspend the - calling thread until certain signals are emitted. These functions - can be used to implement blocking serial ports: - - \list - - \li waitForReadyRead() blocks calls until new data is available for - reading. - - \li waitForBytesWritten() blocks calls until one payload of data has - been written to the serial port. - - \endlist - - See the following example: - - \code - int numRead = 0, numReadTotal = 0; - char buffer[50]; - - for (;;) { - numRead = serial.read(buffer, 50); - - // Do whatever with the array - - numReadTotal += numRead; - if (numRead == 0 && !serial.waitForReadyRead()) - break; - } - \endcode - - If \l{QIODevice::}{waitForReadyRead()} returns \c false, the - connection has been closed or an error has occurred. - - If an error occurs at any point in time, QSerialPort will emit the - errorOccurred() signal. You can also call error() to find the type of - error that occurred last. - - Programming with a blocking serial port is radically different from - programming with a non-blocking serial port. A blocking serial port - does not require an event loop and typically leads to simpler code. - However, in a GUI application, blocking serial port should only be - used in non-GUI threads, to avoid freezing the user interface. - - For more details about these approaches, refer to the - \l {Qt Serial Port Examples}{example} applications. - - The QSerialPort class can also be used with QTextStream and QDataStream's - stream operators (operator<<() and operator>>()). There is one issue to be - aware of, though: make sure that enough data is available before attempting - to read by using the operator>>() overloaded operator. - - \sa QSerialPortInfo -*/ - -/*! - \enum QSerialPort::Direction - - This enum describes the possible directions of the data transmission. - - \note This enumeration is used for setting the baud rate of the device - separately for each direction on some operating systems (for example, - POSIX-like). - - \value Input Input direction. - \value Output Output direction. - \value AllDirections Simultaneously in two directions. -*/ - -/*! - \enum QSerialPort::BaudRate - - This enum describes the baud rate which the communication device operates - with. - - \note Only the most common standard baud rates are listed in this enum. - - \value Baud1200 1200 baud. - \value Baud2400 2400 baud. - \value Baud4800 4800 baud. - \value Baud9600 9600 baud. - \value Baud19200 19200 baud. - \value Baud38400 38400 baud. - \value Baud57600 57600 baud. - \value Baud115200 115200 baud. - - \sa QSerialPort::baudRate -*/ - -/*! - \enum QSerialPort::DataBits - - This enum describes the number of data bits used. - - \value Data5 The number of data bits in each character is 5. It - is used for Baudot code. It generally only makes - sense with older equipment such as teleprinters. - \value Data6 The number of data bits in each character is 6. It - is rarely used. - \value Data7 The number of data bits in each character is 7. It - is used for true ASCII. It generally only makes - sense with older equipment such as teleprinters. - \value Data8 The number of data bits in each character is 8. It - is used for most kinds of data, as this size matches - the size of a byte. It is almost universally used in - newer applications. - - \sa QSerialPort::dataBits -*/ - -/*! - \enum QSerialPort::Parity - - This enum describes the parity scheme used. - - \value NoParity No parity bit it sent. This is the most common - parity setting. Error detection is handled by the - communication protocol. - \value EvenParity The number of 1 bits in each character, including - the parity bit, is always even. - \value OddParity The number of 1 bits in each character, including - the parity bit, is always odd. It ensures that at - least one state transition occurs in each character. - \value SpaceParity Space parity. The parity bit is sent in the space - signal condition. It does not provide error - detection information. - \value MarkParity Mark parity. The parity bit is always set to the - mark signal condition (logical 1). It does not - provide error detection information. - - \sa QSerialPort::parity -*/ - -/*! - \enum QSerialPort::StopBits - - This enum describes the number of stop bits used. - - \value OneStop 1 stop bit. - \value OneAndHalfStop 1.5 stop bits. This is only for the Windows platform. - \value TwoStop 2 stop bits. - - \sa QSerialPort::stopBits -*/ - -/*! - \enum QSerialPort::FlowControl - - This enum describes the flow control used. - - \value NoFlowControl No flow control. - \value HardwareControl Hardware flow control (RTS/CTS). - \value SoftwareControl Software flow control (XON/XOFF). - - \sa QSerialPort::flowControl -*/ - -/*! - \enum QSerialPort::PinoutSignal - - This enum describes the possible RS-232 pinout signals. - - \value NoSignal No line active - \value DataTerminalReadySignal DTR (Data Terminal Ready). - \value DataCarrierDetectSignal DCD (Data Carrier Detect). - \value DataSetReadySignal DSR (Data Set Ready). - \value RingIndicatorSignal RNG (Ring Indicator). - \value RequestToSendSignal RTS (Request To Send). - \value ClearToSendSignal CTS (Clear To Send). - \value SecondaryTransmittedDataSignal STD (Secondary Transmitted Data). - \value SecondaryReceivedDataSignal SRD (Secondary Received Data). - - \sa pinoutSignals(), QSerialPort::dataTerminalReady, - QSerialPort::requestToSend -*/ - -/*! - \enum QSerialPort::SerialPortError - - This enum describes the errors that may be contained by the - QSerialPort::error property. - - \value NoError No error occurred. - - \value DeviceNotFoundError An error occurred while attempting to - open an non-existing device. - - \value PermissionError An error occurred while attempting to - open an already opened device by another - process or a user not having enough permission - and credentials to open. - - \value OpenError An error occurred while attempting to open an - already opened device in this object. - - \value NotOpenError This error occurs when an operation is executed - that can only be successfully performed if the - device is open. This value was introduced in - QtSerialPort 5.2. - - \value WriteError An I/O error occurred while writing the data. - - \value ReadError An I/O error occurred while reading the data. - - \value ResourceError An I/O error occurred when a resource becomes - unavailable, e.g. when the device is - unexpectedly removed from the system. - - \value UnsupportedOperationError The requested device operation is not - supported or prohibited by the running operating - system. - - \value TimeoutError A timeout error occurred. This value was - introduced in QtSerialPort 5.2. - - \value UnknownError An unidentified error occurred. - \sa QSerialPort::error -*/ - -/*! - Constructs a new serial port object with the given \a parent. -*/ -QSerialPort::QSerialPort(QObject* parent) : QIODevice(*new QSerialPortPrivate, parent) -{ -} - -/*! - Constructs a new serial port object with the given \a parent - to represent the serial port with the specified \a name. - - The name should have a specific format; see the setPort() method. -*/ -QSerialPort::QSerialPort(const QString& name, QObject* parent) : QIODevice(*new QSerialPortPrivate, parent) -{ - setPortName(name); -} - -/*! - Constructs a new serial port object with the given \a parent - to represent the serial port with the specified helper class - \a serialPortInfo. -*/ -QSerialPort::QSerialPort(const QSerialPortInfo& serialPortInfo, QObject* parent) - : QIODevice(*new QSerialPortPrivate, parent) -{ - setPort(serialPortInfo); -} - -/*! - Closes the serial port, if necessary, and then destroys object. -*/ -QSerialPort::~QSerialPort() -{ - /**/ - if (isOpen()) - close(); -} - -/*! - Sets the \a name of the serial port. - - The name of the serial port can be passed as either a short name or - the long system location if necessary. - - \sa portName(), QSerialPortInfo -*/ -void QSerialPort::setPortName(const QString& name) -{ - Q_D(QSerialPort); - d->systemLocation = QSerialPortInfoPrivate::portNameToSystemLocation(name); -} - -/*! - Sets the port stored in the serial port info instance \a serialPortInfo. - - \sa portName(), QSerialPortInfo -*/ -void QSerialPort::setPort(const QSerialPortInfo& serialPortInfo) -{ - Q_D(QSerialPort); - d->systemLocation = serialPortInfo.systemLocation(); -} - -/*! - Returns the name set by setPort() or passed to the QSerialPort constructor. - This name is short, i.e. it is extracted and converted from the internal - variable system location of the device. The conversion algorithm is - platform specific: - \table - \header - \li Platform - \li Brief Description - \row - \li Windows - \li Removes the prefix "\\\\.\\" or "//./" from the system location - and returns the remainder of the string. - \row - \li Unix, BSD - \li Removes the prefix "/dev/" from the system location - and returns the remainder of the string. - \endtable - - \sa setPort(), QSerialPortInfo::portName() -*/ -QString QSerialPort::portName() const -{ - Q_D(const QSerialPort); - return QSerialPortInfoPrivate::portNameFromSystemLocation(d->systemLocation); -} - -/*! - \reimp - - Opens the serial port using OpenMode \a mode, and then returns \c true if - successful; otherwise returns \c false and sets an error code which can be - obtained by calling the error() method. - - \note The method returns \c false if opening the port is successful, but could - not set any of the port settings successfully. In that case, the port is - closed automatically not to leave the port around with incorrect settings. - - \warning The \a mode has to be QIODeviceBase::ReadOnly, QIODeviceBase::WriteOnly, - or QIODeviceBase::ReadWrite. Other modes are unsupported. - - \sa QIODeviceBase::OpenMode, setPort() -*/ -bool QSerialPort::open(OpenMode mode) -{ - Q_D(QSerialPort); - - if (isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::OpenError)); - return false; - } - - // Define while not supported modes. - static const OpenMode unsupportedModes = Append | Truncate | Text | Unbuffered; - if ((mode & unsupportedModes) || mode == NotOpen) { - d->setError(QSerialPortErrorInfo(QSerialPort::UnsupportedOperationError, tr("Unsupported open mode"))); - return false; - } - - clearError(); - if (!d->open(mode)) - return false; - - QIODevice::open(mode); - return true; -} - -/*! - \reimp - - \note The serial port has to be open before trying to close it; otherwise - sets the NotOpenError error code. - - \sa QIODevice::close() -*/ -void QSerialPort::close() -{ - Q_D(QSerialPort); - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - return; - } - - d->close(); - d->isBreakEnabled.setValue(false); - QIODevice::close(); -} - -/*! - \property QSerialPort::baudRate - \brief the data baud rate for the desired direction - - If the setting is successful or set before opening the port, returns \c true; - otherwise returns \c false and sets an error code which can be obtained by - accessing the value of the QSerialPort::error property. To set the baud - rate, use the enumeration QSerialPort::BaudRate or any positive qint32 - value. - - \note If the setting is set before opening the port, the actual serial port - setting is done automatically in the \l{QSerialPort::open()} method right - after that the opening of the port succeeds. - - \warning Setting the AllDirections flag is supported on all platforms. - Windows supports only this mode. - - \warning Returns equal baud rate in any direction on Windows. - - The default value is Baud9600, i.e. 9600 bits per second. -*/ -bool QSerialPort::setBaudRate(qint32 baudRate, Directions directions) -{ - Q_D(QSerialPort); - - if (!isOpen() || d->setBaudRate(baudRate, directions)) { - if (directions & QSerialPort::Input) { - if (d->inputBaudRate != baudRate) - d->inputBaudRate = baudRate; - else - directions &= ~QSerialPort::Input; - } - - if (directions & QSerialPort::Output) { - if (d->outputBaudRate != baudRate) - d->outputBaudRate = baudRate; - else - directions &= ~QSerialPort::Output; - } - - if (directions) - emit baudRateChanged(baudRate, directions); - - return true; - } - - return false; -} - -qint32 QSerialPort::baudRate(Directions directions) const -{ - Q_D(const QSerialPort); - if (directions == QSerialPort::AllDirections) - return d->inputBaudRate == d->outputBaudRate ? d->inputBaudRate : -1; - return directions & QSerialPort::Input ? d->inputBaudRate : d->outputBaudRate; -} - -/*! - \fn void QSerialPort::baudRateChanged(qint32 baudRate, Directions directions) - - This signal is emitted after the baud rate has been changed. The new baud - rate is passed as \a baudRate and directions as \a directions. - - \sa QSerialPort::baudRate -*/ - -/*! - \property QSerialPort::dataBits - \brief the data bits in a frame - - If the setting is successful or set before opening the port, returns - \c true; otherwise returns \c false and sets an error code which can be obtained - by accessing the value of the QSerialPort::error property. - - \note If the setting is set before opening the port, the actual serial port - setting is done automatically in the \l{QSerialPort::open()} method right - after that the opening of the port succeeds. - - The default value is Data8, i.e. 8 data bits. -*/ -bool QSerialPort::setDataBits(DataBits dataBits) -{ - Q_D(QSerialPort); - d->dataBits.removeBindingUnlessInWrapper(); - const auto currentDataBits = d->dataBits.valueBypassingBindings(); - if (!isOpen() || d->setDataBits(dataBits)) { - d->dataBits.setValueBypassingBindings(dataBits); - if (currentDataBits != dataBits) { - d->dataBits.notify(); - emit dataBitsChanged(dataBits); - } - return true; - } - return false; -} - -QSerialPort::DataBits QSerialPort::dataBits() const -{ - Q_D(const QSerialPort); - return d->dataBits; -} - -QBindable QSerialPort::bindableDataBits() -{ - return &d_func()->dataBits; -} - -/*! - \fn void QSerialPort::dataBitsChanged(DataBits dataBits) - - This signal is emitted after the data bits in a frame has been changed. The - new data bits in a frame is passed as \a dataBits. - - \sa QSerialPort::dataBits -*/ - -/*! - \property QSerialPort::parity - \brief the parity checking mode - - If the setting is successful or set before opening the port, returns \c true; - otherwise returns \c false and sets an error code which can be obtained by - accessing the value of the QSerialPort::error property. - - \note If the setting is set before opening the port, the actual serial port - setting is done automatically in the \l{QSerialPort::open()} method right - after that the opening of the port succeeds. - - The default value is NoParity, i.e. no parity. -*/ -bool QSerialPort::setParity(Parity parity) -{ - Q_D(QSerialPort); - d->parity.removeBindingUnlessInWrapper(); - const auto currentParity = d->parity.valueBypassingBindings(); - if (!isOpen() || d->setParity(parity)) { - d->parity.setValueBypassingBindings(parity); - if (currentParity != parity) { - d->parity.notify(); - emit parityChanged(parity); - } - return true; - } - return false; -} - -QSerialPort::Parity QSerialPort::parity() const -{ - Q_D(const QSerialPort); - return d->parity; -} - -QBindable QSerialPort::bindableParity() -{ - return &d_func()->parity; -} - -/*! - \fn void QSerialPort::parityChanged(Parity parity) - - This signal is emitted after the parity checking mode has been changed. The - new parity checking mode is passed as \a parity. - - \sa QSerialPort::parity -*/ - -/*! - \property QSerialPort::stopBits - \brief the number of stop bits in a frame - - If the setting is successful or set before opening the port, returns \c true; - otherwise returns \c false and sets an error code which can be obtained by - accessing the value of the QSerialPort::error property. - - \note If the setting is set before opening the port, the actual serial port - setting is done automatically in the \l{QSerialPort::open()} method right - after that the opening of the port succeeds. - - The default value is OneStop, i.e. 1 stop bit. -*/ -bool QSerialPort::setStopBits(StopBits stopBits) -{ - Q_D(QSerialPort); - d->stopBits.removeBindingUnlessInWrapper(); - const auto currentStopBits = d->stopBits.valueBypassingBindings(); - if (!isOpen() || d->setStopBits(stopBits)) { - d->stopBits.setValueBypassingBindings(stopBits); - if (currentStopBits != stopBits) { - d->stopBits.notify(); - emit stopBitsChanged(stopBits); - } - return true; - } - return false; -} - -QSerialPort::StopBits QSerialPort::stopBits() const -{ - Q_D(const QSerialPort); - return d->stopBits; -} - -QBindable QSerialPort::bindableStopBits() -{ - return &d_func()->stopBits; -} - -/*! - \fn void QSerialPort::stopBitsChanged(StopBits stopBits) - - This signal is emitted after the number of stop bits in a frame has been - changed. The new number of stop bits in a frame is passed as \a stopBits. - - \sa QSerialPort::stopBits -*/ - -/*! - \property QSerialPort::flowControl - \brief the desired flow control mode - - If the setting is successful or set before opening the port, returns \c true; - otherwise returns \c false and sets an error code which can be obtained by - accessing the value of the QSerialPort::error property. - - \note If the setting is set before opening the port, the actual serial port - setting is done automatically in the \l{QSerialPort::open()} method right - after that the opening of the port succeeds. - - The default value is NoFlowControl, i.e. no flow control. -*/ -bool QSerialPort::setFlowControl(FlowControl flowControl) -{ - Q_D(QSerialPort); - d->flowControl.removeBindingUnlessInWrapper(); - const auto currentFlowControl = d->flowControl.valueBypassingBindings(); - if (!isOpen() || d->setFlowControl(flowControl)) { - d->flowControl.setValueBypassingBindings(flowControl); - if (currentFlowControl != flowControl) { - d->flowControl.notify(); - emit flowControlChanged(flowControl); - } - return true; - } - return false; -} - -QSerialPort::FlowControl QSerialPort::flowControl() const -{ - Q_D(const QSerialPort); - return d->flowControl; -} - -QBindable QSerialPort::bindableFlowControl() -{ - return &d_func()->flowControl; -} - -/*! - \fn void QSerialPort::flowControlChanged(FlowControl flow) - - This signal is emitted after the flow control mode has been changed. The - new flow control mode is passed as \a flow. - - \sa QSerialPort::flowControl -*/ - -/*! - \property QSerialPort::dataTerminalReady - \brief the state (high or low) of the line signal DTR - - Returns \c true on success, \c false otherwise. - If the flag is \c true then the DTR signal is set to high; otherwise low. - - \note The serial port has to be open before trying to set or get this - property; otherwise \c false is returned and the error code is set to - NotOpenError. - - \sa pinoutSignals() -*/ -bool QSerialPort::setDataTerminalReady(bool set) -{ - Q_D(QSerialPort); - - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - return false; - } - - const bool dataTerminalReady = isDataTerminalReady(); - const bool retval = d->setDataTerminalReady(set); - if (retval && (dataTerminalReady != set)) - emit dataTerminalReadyChanged(set); - - return retval; -} - -bool QSerialPort::isDataTerminalReady() -{ - Q_D(QSerialPort); - return d->pinoutSignals() & QSerialPort::DataTerminalReadySignal; -} - -/*! - \fn void QSerialPort::dataTerminalReadyChanged(bool set) - - This signal is emitted after the state (high or low) of the line signal DTR - has been changed. The new the state (high or low) of the line signal DTR is - passed as \a set. - - \sa QSerialPort::dataTerminalReady -*/ - -/*! - \property QSerialPort::requestToSend - \brief the state (high or low) of the line signal RTS - - Returns \c true on success, \c false otherwise. - If the flag is \c true then the RTS signal is set to high; otherwise low. - - \note The serial port has to be open before trying to set or get this - property; otherwise \c false is returned and the error code is set to - NotOpenError. - - \note An attempt to control the RTS signal in the HardwareControl mode - will fail with error code set to UnsupportedOperationError, because - the signal is automatically controlled by the driver. - - \sa pinoutSignals() -*/ -bool QSerialPort::setRequestToSend(bool set) -{ - Q_D(QSerialPort); - - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - return false; - } - - if (d->flowControl == QSerialPort::HardwareControl) { - d->setError(QSerialPortErrorInfo(QSerialPort::UnsupportedOperationError)); - return false; - } - - const bool requestToSend = isRequestToSend(); - const bool retval = d->setRequestToSend(set); - if (retval && (requestToSend != set)) - emit requestToSendChanged(set); - - return retval; -} - -bool QSerialPort::isRequestToSend() -{ - Q_D(QSerialPort); - return d->pinoutSignals() & QSerialPort::RequestToSendSignal; -} - -/*! - \fn void QSerialPort::requestToSendChanged(bool set) - - This signal is emitted after the state (high or low) of the line signal RTS - has been changed. The new the state (high or low) of the line signal RTS is - passed as \a set. - - \sa QSerialPort::requestToSend -*/ - -/*! - Returns the state of the line signals in a bitmap format. - - From this result, it is possible to allocate the state of the - desired signal by applying a mask "AND", where the mask is - the desired enumeration value from QSerialPort::PinoutSignals. - - \note This method performs a system call, thus ensuring that the line signal - states are returned properly. This is necessary when the underlying - operating systems cannot provide proper notifications about the changes. - - \note The serial port has to be open before trying to get the pinout - signals; otherwise returns NoSignal and sets the NotOpenError error code. - - \sa QSerialPort::dataTerminalReady, QSerialPort::requestToSend -*/ -QSerialPort::PinoutSignals QSerialPort::pinoutSignals() -{ - Q_D(QSerialPort); - - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - return QSerialPort::NoSignal; - } - - return d->pinoutSignals(); -} - -/*! - This function writes as much as possible from the internal write - buffer to the underlying serial port without blocking. If any data - was written, this function returns \c true; otherwise returns \c false. - - Call this function for sending the buffered data immediately to the serial - port. The number of bytes successfully written depends on the operating - system. In most cases, this function does not need to be called, because the - QSerialPort class will start sending data automatically once control is - returned to the event loop. In the absence of an event loop, call - waitForBytesWritten() instead. - - \note The serial port has to be open before trying to flush any buffered - data; otherwise returns \c false and sets the NotOpenError error code. - - \sa write(), waitForBytesWritten() -*/ -bool QSerialPort::flush() -{ - Q_D(QSerialPort); - - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - return false; - } - - return d->flush(); -} - -/*! - Discards all characters from the output or input buffer, depending on - given directions \a directions. This includes clearing the internal class buffers and - the UART (driver) buffers. Also terminate pending read or write operations. - If successful, returns \c true; otherwise returns \c false. - - \note The serial port has to be open before trying to clear any buffered - data; otherwise returns \c false and sets the NotOpenError error code. -*/ -bool QSerialPort::clear(Directions directions) -{ - Q_D(QSerialPort); - - if (!isOpen()) { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - return false; - } - - if (directions & Input) { - QMutexLocker locker(&d->_readMutex); - d->buffer.clear(); - d->_pendingData.clear(); - d->_bufferBytesEstimate.store(0, std::memory_order_relaxed); - } - if (directions & Output) - d->writeBuffer.clear(); - return d->clear(directions); -} - -/*! - \property QSerialPort::error - \brief the error status of the serial port - - The I/O device status returns an error code. For example, if open() - returns \c false, or a read/write operation returns \c -1, this property can - be used to figure out the reason why the operation failed. - - The error code is set to the default QSerialPort::NoError after a call to - clearError() -*/ -QSerialPort::SerialPortError QSerialPort::error() const -{ - Q_D(const QSerialPort); - return d->error; -} - -void QSerialPort::clearError() -{ - Q_D(QSerialPort); - d->setError(QSerialPortErrorInfo(QSerialPort::NoError)); -} - -QBindable QSerialPort::bindableError() const -{ - return &d_func()->error; -} - -/*! - \fn void QSerialPort::errorOccurred(SerialPortError error) - \since 5.8 - - This signal is emitted when an error occurs in the serial port. - The specified \a error describes the type of error that occurred. - - \sa QSerialPort::error -*/ - -/*! - Returns the size of the internal read buffer. This limits the - amount of data that the client can receive before calling the read() - or readAll() methods. - - A read buffer size of \c 0 (the default) means that the buffer has - no size limit, ensuring that no data is lost. - - \sa setReadBufferSize(), read() -*/ -qint64 QSerialPort::readBufferSize() const -{ - Q_D(const QSerialPort); - return d->readBufferMaxSize; -} - -/*! - Sets the size of QSerialPort's internal read buffer to be \a - size bytes. - - If the buffer size is limited to a certain size, QSerialPort - will not buffer more than this size of data. The special case of a buffer - size of \c 0 means that the read buffer is unlimited and all - incoming data is buffered. This is the default. - - This option is useful if the data is only read at certain points - in time (for instance in a real-time streaming application) or if the serial - port should be protected against receiving too much data, which may - eventually cause the application to run out of memory. - - \sa readBufferSize(), read() -*/ -void QSerialPort::setReadBufferSize(qint64 size) -{ - Q_D(QSerialPort); - d->readBufferMaxSize = size; - if (isReadable()) - d->startAsyncRead(); -} - -/*! - \reimp - - Always returns \c true. The serial port is a sequential device. -*/ -bool QSerialPort::isSequential() const -{ - return true; -} - -/*! - \reimp - - Returns the number of incoming bytes that are waiting to be read. - - \sa bytesToWrite(), read() -*/ -qint64 QSerialPort::bytesAvailable() const -{ - return QIODevice::bytesAvailable(); -} - -/*! - \reimp - - Returns the number of bytes that are waiting to be written. The - bytes are written when control goes back to the event loop or - when flush() is called. - - \sa bytesAvailable(), flush() -*/ -qint64 QSerialPort::bytesToWrite() const -{ - qint64 pendingBytes = QIODevice::bytesToWrite(); - return pendingBytes; -} - -/*! - \reimp - - Returns \c true if a line of data can be read from the serial port; - otherwise returns \c false. - - \sa readLine() -*/ -bool QSerialPort::canReadLine() const -{ - return QIODevice::canReadLine(); -} - -/*! - \reimp - - This function blocks until new data is available for reading and the - \l{QIODevice::}{readyRead()} signal has been emitted. The function - will timeout after \a msecs milliseconds; the default timeout is - 30000 milliseconds. If \a msecs is -1, this function will not time out. - - The function returns \c true if the readyRead() signal is emitted and - there is new data available for reading; otherwise it returns \c false - (if an error occurred or the operation timed out). - - \sa waitForBytesWritten() -*/ -bool QSerialPort::waitForReadyRead(int msecs) -{ - Q_D(QSerialPort); - return d->waitForReadyRead(msecs); -} - -/*! - \fn Handle QSerialPort::handle() const - \since 5.2 - - If the platform is supported and the serial port is open, returns the native - serial port handle; otherwise returns \c -1. - - \warning This function is for expert use only; use it at your own risk. - Furthermore, this function carries no compatibility promise between minor - Qt releases. -*/ - -/*! - \reimp - - This function blocks until at least one byte has been written to the serial - port and the \l{QIODevice::}{bytesWritten()} signal has been emitted. The - function will timeout after \a msecs milliseconds; the default timeout is - 30000 milliseconds. If \a msecs is -1, this function will not time out. - - The function returns \c true if the bytesWritten() signal is emitted; otherwise - it returns \c false (if an error occurred or the operation timed out). -*/ -bool QSerialPort::waitForBytesWritten(int msecs) -{ - Q_D(QSerialPort); - return d->waitForBytesWritten(msecs); -} - -/*! - \property QSerialPort::breakEnabled - \since 5.5 - \brief the state of the transmission line in break - - Returns \c true on success, \c false otherwise. - If the flag is \c true then the transmission line is in break state; - otherwise is in non-break state. - - \note The serial port has to be open before trying to set or get this - property; otherwise returns \c false and sets the NotOpenError error code. - This is a bit unusual as opposed to the regular Qt property settings of - a class. However, this is a special use case since the property is set - through the interaction with the kernel and hardware. Hence, the two - scenarios cannot be completely compared to each other. -*/ -bool QSerialPort::setBreakEnabled(bool set) -{ - Q_D(QSerialPort); - d->isBreakEnabled.removeBindingUnlessInWrapper(); - const auto currentSet = d->isBreakEnabled.valueBypassingBindings(); - if (isOpen()) { - if (d->setBreakEnabled(set)) { - d->isBreakEnabled.setValueBypassingBindings(set); - if (currentSet != set) { - d->isBreakEnabled.notify(); - emit breakEnabledChanged(set); - } - return true; - } - } else { - d->setError(QSerialPortErrorInfo(QSerialPort::NotOpenError)); - qWarning("%s: device not open", Q_FUNC_INFO); - } - return false; -} - -bool QSerialPort::isBreakEnabled() const -{ - Q_D(const QSerialPort); - return d->isBreakEnabled; -} - -QBindable QSerialPort::bindableIsBreakEnabled() -{ - return &d_func()->isBreakEnabled; -} - -/*! - \reimp - - \omit - This function does not really read anything, as we use QIODevicePrivate's - buffer. The buffer will be read inside of QIODevice before this - method will be called. - \endomit -*/ -qint64 QSerialPort::readData(char* data, qint64 maxSize) -{ - Q_UNUSED(data); - Q_UNUSED(maxSize); - - // QIODevice drains from d->buffer before calling here; refresh estimate so - // Android read-backpressure tracks current buffered bytes. - d_func()->_bufferBytesEstimate.store(d_func()->buffer.size(), std::memory_order_relaxed); - - // In any case we need to start the notifications if they were - // disabled by the read handler. If enabled, next call does nothing. - d_func()->startAsyncRead(); - - // return 0 indicating there may be more data in the future - return qint64(0); -} - -/*! - \reimp -*/ -qint64 QSerialPort::readLineData(char* data, qint64 maxSize) -{ - return QIODevice::readLineData(data, maxSize); -} - -/*! - \reimp -*/ -qint64 QSerialPort::writeData(const char* data, qint64 maxSize) -{ - Q_D(QSerialPort); - return d->writeData(data, maxSize); -} - -QT_END_NAMESPACE - -#include "moc_qserialport.cpp" diff --git a/src/Android/qtandroidserialport/qserialport.h b/src/Android/qtandroidserialport/qserialport.h deleted file mode 100644 index 4406d2b4cc52..000000000000 --- a/src/Android/qtandroidserialport/qserialport.h +++ /dev/null @@ -1,213 +0,0 @@ -// Copyright (C) 2012 Denis Shienkov -// Copyright (C) 2013 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -#include - -#include "qserialportglobal.h" - -QT_BEGIN_NAMESPACE - -class QSerialPortInfo; -class QSerialPortPrivate; - -class Q_SERIALPORT_EXPORT QSerialPort : public QIODevice -{ - Q_OBJECT - Q_DECLARE_PRIVATE(QSerialPort) - - Q_PROPERTY(qint32 baudRate READ baudRate WRITE setBaudRate NOTIFY baudRateChanged) - Q_PROPERTY(DataBits dataBits READ dataBits WRITE setDataBits NOTIFY dataBitsChanged BINDABLE bindableDataBits) - Q_PROPERTY(Parity parity READ parity WRITE setParity NOTIFY parityChanged BINDABLE bindableParity) - Q_PROPERTY(StopBits stopBits READ stopBits WRITE setStopBits NOTIFY stopBitsChanged BINDABLE bindableStopBits) - Q_PROPERTY(FlowControl flowControl READ flowControl WRITE setFlowControl NOTIFY flowControlChanged BINDABLE - bindableFlowControl) - Q_PROPERTY( - bool dataTerminalReady READ isDataTerminalReady WRITE setDataTerminalReady NOTIFY dataTerminalReadyChanged) - Q_PROPERTY(bool requestToSend READ isRequestToSend WRITE setRequestToSend NOTIFY requestToSendChanged) - Q_PROPERTY(SerialPortError error READ error RESET clearError NOTIFY errorOccurred BINDABLE bindableError) - Q_PROPERTY(bool breakEnabled READ isBreakEnabled WRITE setBreakEnabled NOTIFY breakEnabledChanged BINDABLE - bindableIsBreakEnabled) - - typedef int Handle; - -public: - enum Direction - { - Input = 1, - Output = 2, - AllDirections = Input | Output - }; - Q_FLAG(Direction) - Q_DECLARE_FLAGS(Directions, Direction) - - enum BaudRate - { - Baud1200 = 1200, - Baud2400 = 2400, - Baud4800 = 4800, - Baud9600 = 9600, - Baud19200 = 19200, - Baud38400 = 38400, - Baud57600 = 57600, - Baud115200 = 115200 - }; - Q_ENUM(BaudRate) - - enum DataBits - { - Data5 = 5, - Data6 = 6, - Data7 = 7, - Data8 = 8 - }; - Q_ENUM(DataBits) - - enum Parity - { - NoParity = 0, - EvenParity = 2, - OddParity = 3, - SpaceParity = 4, - MarkParity = 5 - }; - Q_ENUM(Parity) - - enum StopBits - { - OneStop = 1, - OneAndHalfStop = 3, - TwoStop = 2 - }; - Q_ENUM(StopBits) - - enum FlowControl - { - NoFlowControl, - HardwareControl, - SoftwareControl - }; - Q_ENUM(FlowControl) - - enum PinoutSignal - { - NoSignal = 0x00, - DataTerminalReadySignal = 0x04, - DataCarrierDetectSignal = 0x08, - DataSetReadySignal = 0x10, - RingIndicatorSignal = 0x20, - RequestToSendSignal = 0x40, - ClearToSendSignal = 0x80, - SecondaryTransmittedDataSignal = 0x100, - SecondaryReceivedDataSignal = 0x200 - }; - Q_FLAG(PinoutSignal) - Q_DECLARE_FLAGS(PinoutSignals, PinoutSignal) - - enum SerialPortError - { - NoError, - DeviceNotFoundError, - PermissionError, - OpenError, - WriteError, - ReadError, - ResourceError, - UnsupportedOperationError, - UnknownError, - TimeoutError, - NotOpenError - }; - Q_ENUM(SerialPortError) - - explicit QSerialPort(QObject* parent = nullptr); - explicit QSerialPort(const QString& name, QObject* parent = nullptr); - explicit QSerialPort(const QSerialPortInfo& info, QObject* parent = nullptr); - virtual ~QSerialPort(); - - void setPortName(const QString& name); - QString portName() const; - - void setPort(const QSerialPortInfo& info); - - bool open(OpenMode mode) override; - void close() override; - - bool setBaudRate(qint32 baudRate, Directions directions = AllDirections); - qint32 baudRate(Directions directions = AllDirections) const; - - bool setDataBits(DataBits dataBits); - DataBits dataBits() const; - QBindable bindableDataBits(); - - bool setParity(Parity parity); - Parity parity() const; - QBindable bindableParity(); - - bool setStopBits(StopBits stopBits); - StopBits stopBits() const; - QBindable bindableStopBits(); - - bool setFlowControl(FlowControl flowControl); - FlowControl flowControl() const; - QBindable bindableFlowControl(); - - bool setDataTerminalReady(bool set); - bool isDataTerminalReady(); - - bool setRequestToSend(bool set); - bool isRequestToSend(); - - PinoutSignals pinoutSignals(); - - bool flush(); - bool clear(Directions directions = AllDirections); - - SerialPortError error() const; - void clearError(); - QBindable bindableError() const; - - qint64 readBufferSize() const; - void setReadBufferSize(qint64 size); - - bool isSequential() const override; - - qint64 bytesAvailable() const override; - qint64 bytesToWrite() const override; - bool canReadLine() const override; - - bool waitForReadyRead(int msecs = 30000) override; - bool waitForBytesWritten(int msecs = 30000) override; - - bool setBreakEnabled(bool set = true); - bool isBreakEnabled() const; - QBindable bindableIsBreakEnabled(); - - Handle handle() const; - -Q_SIGNALS: - void baudRateChanged(qint32 baudRate, QSerialPort::Directions directions); - void dataBitsChanged(QSerialPort::DataBits dataBits); - void parityChanged(QSerialPort::Parity parity); - void stopBitsChanged(QSerialPort::StopBits stopBits); - void flowControlChanged(QSerialPort::FlowControl flowControl); - void dataTerminalReadyChanged(bool set); - void requestToSendChanged(bool set); - void errorOccurred(QSerialPort::SerialPortError error); - void breakEnabledChanged(bool set); - -protected: - qint64 readData(char* data, qint64 maxSize) override; - qint64 readLineData(char* data, qint64 maxSize) override; - qint64 writeData(const char* data, qint64 maxSize) override; - -private: - Q_DISABLE_COPY(QSerialPort) -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS(QSerialPort::Directions) -Q_DECLARE_OPERATORS_FOR_FLAGS(QSerialPort::PinoutSignals) - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialport_android.cpp b/src/Android/qtandroidserialport/qserialport_android.cpp deleted file mode 100644 index 2357443f344a..000000000000 --- a/src/Android/qtandroidserialport/qserialport_android.cpp +++ /dev/null @@ -1,603 +0,0 @@ -#include -#include -#include - -#include - -#include "QGCLoggingCategory.h" -#include "qserialport_p.h" - -QGC_LOGGING_CATEGORY(AndroidSerialPortLog, "Android.AndroidSerialPort") - -QT_BEGIN_NAMESPACE - -bool QSerialPortPrivate::open(QIODevice::OpenMode mode) -{ - qCDebug(AndroidSerialPortLog) << "Opening" << systemLocation; - - AndroidSerial::registerPointer(this); - auto tokenGuard = qScopeGuard([this]() { AndroidSerial::unregisterPointer(this); }); - - _deviceId = AndroidSerial::open(systemLocation, this); - if (_deviceId == INVALID_DEVICE_ID) { - qCWarning(AndroidSerialPortLog) << "Error opening" << systemLocation; - setError(QSerialPortErrorInfo(QSerialPort::DeviceNotFoundError)); - return false; - } - - descriptor = AndroidSerial::getDeviceHandle(_deviceId); - if (descriptor == -1) { - qCWarning(AndroidSerialPortLog) << "Failed to get device handle for" << systemLocation; - setError(QSerialPortErrorInfo(QSerialPort::OpenError)); - close(); - return false; - } - - if (!_setParameters(inputBaudRate, dataBits, stopBits, parity)) { - qCWarning(AndroidSerialPortLog) << "Failed to set serial port parameters for" << systemLocation; - close(); - return false; - } - - if (!setFlowControl(flowControl)) { - qCWarning(AndroidSerialPortLog) << "Failed to set serial port flow control for" << systemLocation; - close(); - return false; - } - - if (mode & QIODevice::ReadOnly) { - if (!startAsyncRead()) { - qCWarning(AndroidSerialPortLog) << "Failed to start async read for" << systemLocation; - close(); - return false; - } - } else if (mode & QIODevice::WriteOnly) { - if (!_stopAsyncRead()) { - qCWarning(AndroidSerialPortLog) << "Failed to stop async read for" << systemLocation; - } - } - - (void)clear(QSerialPort::AllDirections); - tokenGuard.dismiss(); - - return true; -} - -void QSerialPortPrivate::close() -{ - qCDebug(AndroidSerialPortLog) << "Closing" << systemLocation; - - _stopAsyncRead(); - - if (_deviceId != INVALID_DEVICE_ID) { - if (!AndroidSerial::close(_deviceId)) { - qCWarning(AndroidSerialPortLog) << "Failed to close device with ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Closing device failed"))); - } - _deviceId = INVALID_DEVICE_ID; - } - - descriptor = -1; - - AndroidSerial::unregisterPointer(this); -} - -void QSerialPortPrivate::exceptionArrived(const QString& ex) -{ - qCWarning(AndroidSerialPortLog) << "Exception arrived on device ID" << _deviceId << ":" << ex; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, ex)); -} - -bool QSerialPortPrivate::startAsyncRead() -{ - if (!AndroidSerial::readThreadRunning(_deviceId)) { - const bool result = AndroidSerial::startReadThread(_deviceId); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to start async read thread for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to start async read"))); - return false; - } - } - - // If pending bytes were left behind due to read buffer backpressure, - // schedule another drain as soon as reads are active again. - _scheduleReadyRead(); - - return true; -} - -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"))); - } - } - - return result; -} - -qint64 QSerialPortPrivate::_drainPendingDataLocked(qint64 maxBytes) -{ - const qsizetype pendingSize = _pendingSizeLocked(); - if (pendingSize <= 0) { - _pendingData.clear(); - _pendingDataOffset = 0; - return 0; - } - - qint64 toDrain = pendingSize; - if (maxBytes >= 0) { - toDrain = qMin(toDrain, maxBytes); - } - - if (toDrain <= 0) { - return 0; - } - - buffer.append(_pendingData.constData() + _pendingDataOffset, toDrain); - _pendingDataOffset += static_cast(toDrain); - - if (_pendingDataOffset >= _pendingData.size()) { - _pendingData.clear(); - _pendingDataOffset = 0; - } else { - // Compact occasionally to keep append operations efficient without - // paying the cost on every drain. - constexpr qsizetype kCompactThreshold = 4096; - if (_pendingDataOffset >= kCompactThreshold && (_pendingDataOffset * 2) >= _pendingData.size()) { - _compactPendingDataLocked(); - } - } - - _bufferBytesEstimate.store(buffer.size(), std::memory_order_relaxed); - return toDrain; -} - -qsizetype QSerialPortPrivate::_pendingSizeLocked() const -{ - return qMax(0, _pendingData.size() - _pendingDataOffset); -} - -void QSerialPortPrivate::_compactPendingDataLocked() -{ - if (_pendingDataOffset <= 0) { - return; - } - - if (_pendingDataOffset >= _pendingData.size()) { - _pendingData.clear(); - _pendingDataOffset = 0; - return; - } - - _pendingData.remove(0, _pendingDataOffset); - _pendingDataOffset = 0; -} - -void QSerialPortPrivate::newDataArrived(const char* bytes, int length) -{ - // qCDebug(AndroidSerialPortLog) << "newDataArrived" << length; - - qint64 droppedBytes = 0; - - QMutexLocker locker(&_readMutex); - int bytesToRead = length; - if (readBufferMaxSize) { - const qint64 totalBuffered = _pendingSizeLocked() + _bufferBytesEstimate.load(std::memory_order_relaxed); - const qint64 headroom = readBufferMaxSize - totalBuffered; - if (bytesToRead > headroom) { - bytesToRead = static_cast(qMax(qint64(0), headroom)); - droppedBytes = static_cast(length - bytesToRead); - } - } - - if (bytesToRead > 0) { - constexpr qsizetype kCompactBeforeAppendThreshold = 8192; - if (_pendingDataOffset >= kCompactBeforeAppendThreshold) { - _compactPendingDataLocked(); - } - _pendingData.append(bytes, bytesToRead); - _readWaitCondition.wakeAll(); - } - locker.unlock(); - - if (droppedBytes > 0) { - qCWarning(AndroidSerialPortLog) << "Read buffer full, dropping" << droppedBytes << "bytes"; - } - - if (bytesToRead <= 0) { - return; - } - - _scheduleReadyRead(); -} - -void QSerialPortPrivate::_scheduleReadyRead() -{ - Q_Q(QSerialPort); - - if (!_readyReadPending.exchange(true)) { - QPointer guard(q); - QMetaObject::invokeMethod( - q, - [this, guard]() { - if (!guard) { - return; - } - - QMutexLocker locker(&_readMutex); - if (_pendingSizeLocked() <= 0) { - _readyReadPending.store(false); - return; - } - - if (readBufferMaxSize > 0) { - const qint64 canAccept = readBufferMaxSize - buffer.size(); - if (canAccept > 0) { - (void)_drainPendingDataLocked(canAccept); - } - } else { - (void)_drainPendingDataLocked(); - } - - // Reset flag after drain so data arriving during the drain - // does not enqueue redundant lambdas. If pending data remains, - // reschedule so nothing is left undelivered. - const bool more = (_pendingSizeLocked() > 0); - _readyReadPending.store(false); - - _readWaitCondition.wakeAll(); - locker.unlock(); - - emit guard->readyRead(); - - if (more) { - _scheduleReadyRead(); - } - }, - Qt::QueuedConnection); - } -} - -bool QSerialPortPrivate::waitForReadyRead(int msecs) -{ - QMutexLocker locker(&_readMutex); - if (!buffer.isEmpty()) { - return true; - } - - if (_pendingSizeLocked() > 0) { - (void)_drainPendingDataLocked(); - return true; - } - - QDeadlineTimer deadline(msecs); - while (buffer.isEmpty() && (_pendingSizeLocked() <= 0)) { - if (!_readWaitCondition.wait(&_readMutex, deadline)) { - break; - } - - if (!buffer.isEmpty()) { - return true; - } - - if (_pendingSizeLocked() > 0) { - (void)_drainPendingDataLocked(); - return true; - } - } - 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"))); - - return false; -} - -bool QSerialPortPrivate::waitForBytesWritten(int msecs) -{ - const bool result = _writeDataOneShot(msecs); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Timeout while waiting for bytes written on device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::TimeoutError, - QSerialPort::tr("Timeout while waiting for bytes written"))); - } - - return result; -} - -bool QSerialPortPrivate::_writeDataOneShot(int msecs) -{ - if (writeBuffer.isEmpty()) { - return true; - } - - qint64 pendingBytesWritten = 0; - - while (!writeBuffer.isEmpty()) { - const char* dataPtr = writeBuffer.readPointer(); - 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"))); - return false; - } - - writeBuffer.free(written); - pendingBytesWritten += written; - } - - const bool result = (pendingBytesWritten > 0); - if (result) { - Q_Q(QSerialPort); - emit q->bytesWritten(pendingBytesWritten); - } - - return result; -} - -qint64 QSerialPortPrivate::_writeToPort(const char* data, qint64 maxSize, int timeout, bool async) -{ - 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"))); - } - - return result; -} - -qint64 QSerialPortPrivate::writeData(const char* data, qint64 maxSize) -{ - if (!data || (maxSize <= 0)) { - qCWarning(AndroidSerialPortLog) << "Invalid data or size in writeData for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::WriteError, QSerialPort::tr("Invalid data or size"))); - return -1; - } - - return _writeToPort(data, maxSize); -} - -bool QSerialPortPrivate::flush() -{ - const bool result = _writeDataOneShot(); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Flush operation failed for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to flush"))); - } - - return result; -} - -bool QSerialPortPrivate::clear(QSerialPort::Directions directions) -{ - const bool input = directions & QSerialPort::Input; - const bool output = directions & QSerialPort::Output; - - const bool result = AndroidSerial::purgeBuffers(_deviceId, input, output); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to purge buffers for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to purge buffers"))); - } - - return result; -} - -QSerialPort::PinoutSignals QSerialPortPrivate::pinoutSignals() -{ - return AndroidSerial::getControlLines(_deviceId); -} - -bool QSerialPortPrivate::setDataTerminalReady(bool set) -{ - const bool result = AndroidSerial::setDataTerminalReady(_deviceId, set); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set DTR for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set DTR"))); - } - - return result; -} - -bool QSerialPortPrivate::setRequestToSend(bool set) -{ - const bool result = AndroidSerial::setRequestToSend(_deviceId, set); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set RTS for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set RTS"))); - } - - return result; -} - -bool QSerialPortPrivate::_setParameters(qint32 baudRate, QSerialPort::DataBits dataBits_, - QSerialPort::StopBits stopBits_, QSerialPort::Parity parity_) -{ - const bool result = - AndroidSerial::setParameters(_deviceId, baudRate, _dataBitsToAndroidDataBits(dataBits_), - _stopBitsToAndroidStopBits(stopBits_), _parityToAndroidParity(parity_)); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set Parameters for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set parameters"))); - } - - return result; -} - -bool QSerialPortPrivate::setBaudRate() -{ - return setBaudRate(inputBaudRate, QSerialPort::AllDirections); -} - -bool QSerialPortPrivate::setBaudRate(qint32 baudRate, QSerialPort::Directions directions) -{ - if (baudRate <= 0) { - qCWarning(AndroidSerialPortLog) << "Invalid baud rate value:" << baudRate; - setError( - QSerialPortErrorInfo(QSerialPort::UnsupportedOperationError, QSerialPort::tr("Invalid baud rate value"))); - return false; - } - - if (directions != QSerialPort::AllDirections) { - qCWarning(AndroidSerialPortLog) << "Custom baud rate direction is unsupported:" << directions; - setError(QSerialPortErrorInfo(QSerialPort::UnsupportedOperationError, - QSerialPort::tr("Custom baud rate direction is unsupported"))); - return false; - } - - const bool result = _setParameters(baudRate, dataBits, stopBits, parity); - if (result) { - inputBaudRate = outputBaudRate = baudRate; - } else { - qCWarning(AndroidSerialPortLog) << "Failed to set baud rate for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set baud rate"))); - } - - return result; -} - -int QSerialPortPrivate::_dataBitsToAndroidDataBits(QSerialPort::DataBits dataBits_) -{ - switch (dataBits_) { - case QSerialPort::Data5: - return AndroidSerial::Data5; - case QSerialPort::Data6: - return AndroidSerial::Data6; - case QSerialPort::Data7: - return AndroidSerial::Data7; - case QSerialPort::Data8: - return AndroidSerial::Data8; - default: - qCWarning(AndroidSerialPortLog) << "Invalid Data Bits" << dataBits_; - return AndroidSerial::Data8; // Default to Data8 - } -} - -bool QSerialPortPrivate::setDataBits(QSerialPort::DataBits dataBits_) -{ - const bool result = _setParameters(inputBaudRate, dataBits_, stopBits, parity); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set data bits for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set data bits"))); - } - - return result; -} - -int QSerialPortPrivate::_parityToAndroidParity(QSerialPort::Parity parity_) -{ - switch (parity_) { - case QSerialPort::SpaceParity: - return AndroidSerial::SpaceParity; - case QSerialPort::MarkParity: - return AndroidSerial::MarkParity; - case QSerialPort::EvenParity: - return AndroidSerial::EvenParity; - case QSerialPort::OddParity: - return AndroidSerial::OddParity; - case QSerialPort::NoParity: - return AndroidSerial::NoParity; - default: - qCWarning(AndroidSerialPortLog) << "Invalid parity type:" << parity_; - return AndroidSerial::NoParity; // Default to NoParity - } -} - -bool QSerialPortPrivate::setParity(QSerialPort::Parity parity_) -{ - const bool result = _setParameters(inputBaudRate, dataBits, stopBits, parity_); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set parity for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set parity"))); - } - - return result; -} - -int QSerialPortPrivate::_stopBitsToAndroidStopBits(QSerialPort::StopBits stopBits_) -{ - switch (stopBits_) { - case QSerialPort::TwoStop: - return AndroidSerial::TwoStop; - case QSerialPort::OneAndHalfStop: - return AndroidSerial::OneAndHalfStop; - case QSerialPort::OneStop: - return AndroidSerial::OneStop; - default: - qCWarning(AndroidSerialPortLog) << "Invalid Stop Bits type:" << stopBits_; - return AndroidSerial::OneStop; // Default to OneStop - } -} - -bool QSerialPortPrivate::setStopBits(QSerialPort::StopBits stopBits_) -{ - const bool result = _setParameters(inputBaudRate, dataBits, stopBits_, parity); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set StopBits for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set StopBits"))); - } - - return result; -} - -int QSerialPortPrivate::_flowControlToAndroidFlowControl(QSerialPort::FlowControl flowControl_) -{ - switch (flowControl_) { - case QSerialPort::HardwareControl: - return AndroidSerial::RtsCtsFlowControl; - case QSerialPort::SoftwareControl: - return AndroidSerial::XonXoffFlowControl; - case QSerialPort::NoFlowControl: - return AndroidSerial::NoFlowControl; - default: - qCWarning(AndroidSerialPortLog) << "Invalid Flow Control type:" << flowControl_; - return AndroidSerial::NoFlowControl; // Default to NoFlowControl - } -} - -bool QSerialPortPrivate::setFlowControl(QSerialPort::FlowControl flowControl_) -{ - const bool result = AndroidSerial::setFlowControl(_deviceId, _flowControlToAndroidFlowControl(flowControl_)); - if (!result) { - qCWarning(AndroidSerialPortLog) << "Failed to set Flow Control for device ID" << _deviceId; - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set Flow Control"))); - } - - return result; -} - -bool QSerialPortPrivate::setBreakEnabled(bool set) -{ - const bool result = AndroidSerial::setBreak(_deviceId, set); - if (!result) { - setError(QSerialPortErrorInfo(QSerialPort::UnknownError, QSerialPort::tr("Failed to set Break Enabled"))); - } - - return result; -} - -static constexpr qint32 kStandardBaudRates[] = { - 50, 75, 110, 134, 150, 200, 300, 600, 1200, 1800, - 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 460800, 500000, - 576000, 921600, 1000000, 1152000, 1500000, 2000000, 2500000, 3000000, 3500000, 4000000, -}; - -QList QSerialPortPrivate::standardBaudRates() -{ - return QList(std::begin(kStandardBaudRates), std::end(kStandardBaudRates)); -} - -QSerialPort::Handle QSerialPort::handle() const -{ - Q_D(const QSerialPort); - return d->descriptor; -} - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialport_p.h b/src/Android/qtandroidserialport/qserialport_p.h deleted file mode 100644 index d945a509ef8c..000000000000 --- a/src/Android/qtandroidserialport/qserialport_p.h +++ /dev/null @@ -1,171 +0,0 @@ -// Copyright (C) 2011-2012 Denis Shienkov -// Copyright (C) 2011 Sergey Belyashov -// Copyright (C) 2012 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -// -// W A R N I N G -// ------------- -// -// This file is not part of the Qt API. It exists purely as an -// implementation detail. This header file may change from version to -// version without notice, or even be removed. -// -// We mean it. -// - -#include -#include -#include -#include -#include - -#include - -#include "AndroidSerial.h" -#include "qserialport.h" - -constexpr int INVALID_DEVICE_ID = 0; -constexpr int MIN_READ_TIMEOUT = 500; -constexpr qint64 MAX_READ_SIZE = 16 * 1024; -constexpr qint64 DEFAULT_READ_BUFFER_SIZE = MAX_READ_SIZE; -constexpr qint64 DEFAULT_WRITE_BUFFER_SIZE = 16 * 1024; -constexpr int DEFAULT_WRITE_TIMEOUT = 5000; -constexpr int DEFAULT_READ_TIMEOUT = 0; -constexpr int EMIT_THRESHOLD = 64; - -#ifndef QSERIALPORT_BUFFERSIZE -#define QSERIALPORT_BUFFERSIZE DEFAULT_WRITE_BUFFER_SIZE -#endif - -Q_DECLARE_LOGGING_CATEGORY(AndroidSerialPortLog) - -QT_BEGIN_NAMESPACE - -class QSerialPortErrorInfo -{ -public: - QSerialPortErrorInfo(QSerialPort::SerialPortError newErrorCode = QSerialPort::UnknownError, - const QString& newErrorString = QString()); - QSerialPort::SerialPortError errorCode = QSerialPort::UnknownError; - QString errorString; -}; - -class QSerialPortPrivate : public QIODevicePrivate -{ -public: - Q_DECLARE_PUBLIC(QSerialPort) - - QSerialPortPrivate(); - - bool open(QIODevice::OpenMode mode); - void close(); - - bool flush(); - bool clear(QSerialPort::Directions directions); - - QSerialPort::PinoutSignals pinoutSignals(); - - bool setDataTerminalReady(bool set); - bool setRequestToSend(bool set); - - bool setBaudRate(); - bool setBaudRate(qint32 baudRate, QSerialPort::Directions directions); - bool setDataBits(QSerialPort::DataBits dataBits); - bool setParity(QSerialPort::Parity parity); - bool setStopBits(QSerialPort::StopBits stopBits); - bool setFlowControl(QSerialPort::FlowControl flowControl); - - bool setBreakEnabled(bool set); - - void setError(const QSerialPortErrorInfo& errorInfo); - - void setBindableError(QSerialPort::SerialPortError error_) - { - setError(error_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, QSerialPort::SerialPortError, error, - &QSerialPortPrivate::setBindableError, QSerialPort::NoError) - - bool setBindableDataBits(QSerialPort::DataBits dataBits_) - { - return q_func()->setDataBits(dataBits_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, QSerialPort::DataBits, dataBits, - &QSerialPortPrivate::setBindableDataBits, QSerialPort::Data8) - - bool setBindableParity(QSerialPort::Parity parity_) - { - return q_func()->setParity(parity_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, QSerialPort::Parity, parity, - &QSerialPortPrivate::setBindableParity, QSerialPort::NoParity) - - bool setBindableStopBits(QSerialPort::StopBits stopBits_) - { - return q_func()->setStopBits(stopBits_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, QSerialPort::StopBits, stopBits, - &QSerialPortPrivate::setBindableStopBits, QSerialPort::OneStop) - - bool setBindableFlowControl(QSerialPort::FlowControl flowControl_) - { - return q_func()->setFlowControl(flowControl_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, QSerialPort::FlowControl, flowControl, - &QSerialPortPrivate::setBindableFlowControl, QSerialPort::NoFlowControl) - - bool setBindableBreakEnabled(bool isBreakEnabled_) - { - return q_func()->setBreakEnabled(isBreakEnabled_); - } - Q_OBJECT_COMPAT_PROPERTY_WITH_ARGS(QSerialPortPrivate, bool, isBreakEnabled, - &QSerialPortPrivate::setBindableBreakEnabled, false) - - bool waitForReadyRead(int msec); - bool waitForBytesWritten(int msec); - - bool startAsyncRead(); - - qint64 writeData(const char* data, qint64 maxSize); - - void newDataArrived(const char* bytes, int length); - void exceptionArrived(const QString& ex); - - static QList standardBaudRates(); - - QString systemLocation; - qint32 inputBaudRate = QSerialPort::Baud9600; - qint32 outputBaudRate = QSerialPort::Baud9600; - qint64 readBufferMaxSize = 0; - int descriptor = -1; - -private: - qint64 _writeToPort(const char* data, qint64 maxSize, int timeout = DEFAULT_WRITE_TIMEOUT, bool async = false); - bool _stopAsyncRead(); - void _scheduleReadyRead(); - qsizetype _pendingSizeLocked() const; - void _compactPendingDataLocked(); - qint64 _drainPendingDataLocked(qint64 maxBytes = -1); - bool _setParameters(qint32 baudRate, QSerialPort::DataBits dataBits, QSerialPort::StopBits stopBits, - QSerialPort::Parity parity); - bool _writeDataOneShot(int msecs = DEFAULT_WRITE_TIMEOUT); - - static int _stopBitsToAndroidStopBits(QSerialPort::StopBits stopBits); - static int _dataBitsToAndroidDataBits(QSerialPort::DataBits dataBits); - static int _parityToAndroidParity(QSerialPort::Parity parity); - static int _flowControlToAndroidFlowControl(QSerialPort::FlowControl flowControl); - - int _deviceId = INVALID_DEVICE_ID; - - std::atomic _readyReadPending{false}; - std::atomic _bufferBytesEstimate{0}; - QMutex _readMutex; - QWaitCondition _readWaitCondition; - QByteArray _pendingData; - qsizetype _pendingDataOffset = 0; -}; - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialportglobal.h b/src/Android/qtandroidserialport/qserialportglobal.h deleted file mode 100644 index 3fc7f1410e2c..000000000000 --- a/src/Android/qtandroidserialport/qserialportglobal.h +++ /dev/null @@ -1,9 +0,0 @@ -// Copyright (C) 2012 Denis Shienkov -// Copyright (C) 2012 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -#include -#include -#include "qtserialportexports.h" diff --git a/src/Android/qtandroidserialport/qserialportinfo.cpp b/src/Android/qtandroidserialport/qserialportinfo.cpp deleted file mode 100644 index be58f6948a99..000000000000 --- a/src/Android/qtandroidserialport/qserialportinfo.cpp +++ /dev/null @@ -1,255 +0,0 @@ -// Copyright (C) 2011-2012 Denis Shienkov -// Copyright (C) 2011 Sergey Belyashov -// Copyright (C) 2012 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#include "qserialportinfo.h" -#include "qserialportinfo_p.h" -#include "qserialport.h" -#include "qserialport_p.h" - -QT_BEGIN_NAMESPACE - -// We changed from QScopedPointer to std::unique_ptr, make sure it's -// binary compatible. The QScopedPointer had a non-default deleter, but -// the deleter just provides a static function to use for deletion so we don't -// include it in this template definition (the deleter-class was deleted). -static_assert(sizeof(std::unique_ptr) - == sizeof(QScopedPointer)); - -/*! - \class QSerialPortInfo - - \brief Provides information about existing serial ports. - - \ingroup serialport-main - \inmodule QtSerialPort - \since 5.1 - - Use the static \l availablePorts() function to generate a list of - QSerialPortInfo objects. Each QSerialPortInfo object in the list represents - a single serial port and can be queried for the \l {portName}{port name}, - \l {systemLocation}{system location}, \l description, \l manufacturer, and - some other hardware parameters. The QSerialPortInfo class can also be - used as an input parameter for the \l {QSerialPort::}{setPort()} method of - the QSerialPort class. - - \section1 Example Usage - - The example code enumerates all available serial ports and prints their - parameters to console: - - \snippet doc_src_serialport.cpp enumerate_ports - - \sa QSerialPort -*/ - -/*! - Constructs an empty QSerialPortInfo object. - - \sa isNull() -*/ -QSerialPortInfo::QSerialPortInfo() -{ -} - -/*! - Constructs a copy of \a other. -*/ -QSerialPortInfo::QSerialPortInfo(const QSerialPortInfo &other) - : d_ptr(other.d_ptr ? new QSerialPortInfoPrivate(*other.d_ptr) : nullptr) -{ -} - -/*! - Constructs a QSerialPortInfo object from serial \a port. -*/ -QSerialPortInfo::QSerialPortInfo(const QSerialPort &port) - : QSerialPortInfo(port.portName()) -{ -} - -/*! - Constructs a QSerialPortInfo object from serial port \a name. - - This constructor finds the relevant serial port among the available ones - according to the port name \a name, and constructs the serial port info - instance for that port. -*/ -QSerialPortInfo::QSerialPortInfo(const QString &name) -{ - const auto infos = QSerialPortInfo::availablePorts(); - for (const QSerialPortInfo &info : infos) { - if (name == info.portName()) { - *this = info; - break; - } - } -} - -QSerialPortInfo::QSerialPortInfo(const QSerialPortInfoPrivate &dd) - : d_ptr(new QSerialPortInfoPrivate(dd)) -{ -} - -/*! - Destroys the QSerialPortInfo object. References to the values in the - object become invalid. -*/ -QSerialPortInfo::~QSerialPortInfo() -{ -} - -/*! - Swaps QSerialPortInfo \a other with this QSerialPortInfo. This operation is - very fast and never fails. -*/ -void QSerialPortInfo::swap(QSerialPortInfo &other) -{ - d_ptr.swap(other.d_ptr); -} - -/*! - Sets the QSerialPortInfo object to be equal to \a other. -*/ -QSerialPortInfo& QSerialPortInfo::operator=(const QSerialPortInfo &other) -{ - QSerialPortInfo(other).swap(*this); - return *this; -} - -/*! - Returns the name of the serial port. - - \sa systemLocation() -*/ -QString QSerialPortInfo::portName() const -{ - Q_D(const QSerialPortInfo); - return !d ? QString() : d->portName; -} - -/*! - Returns the system location of the serial port. - - \sa portName() -*/ -QString QSerialPortInfo::systemLocation() const -{ - Q_D(const QSerialPortInfo); - return !d ? QString() : d->device; -} - -/*! - Returns the description string of the serial port, - if available; otherwise returns an empty string. - - \sa manufacturer(), serialNumber() -*/ -QString QSerialPortInfo::description() const -{ - Q_D(const QSerialPortInfo); - return !d ? QString() : d->description; -} - -/*! - Returns the manufacturer string of the serial port, - if available; otherwise returns an empty string. - - \sa description(), serialNumber() -*/ -QString QSerialPortInfo::manufacturer() const -{ - Q_D(const QSerialPortInfo); - return !d ? QString() : d->manufacturer; -} - -/*! - \since 5.3 - - Returns the serial number string of the serial port, - if available; otherwise returns an empty string. - - \note The serial number may include letters. - - \sa description(), manufacturer() -*/ -QString QSerialPortInfo::serialNumber() const -{ - Q_D(const QSerialPortInfo); - return !d ? QString() : d->serialNumber; -} - -/*! - Returns the 16-bit vendor number for the serial port, if available; - otherwise returns zero. - - \sa hasVendorIdentifier(), productIdentifier(), hasProductIdentifier() -*/ -quint16 QSerialPortInfo::vendorIdentifier() const -{ - Q_D(const QSerialPortInfo); - return !d ? 0 : d->vendorIdentifier; -} - -/*! - Returns the 16-bit product number for the serial port, if available; - otherwise returns zero. - - \sa hasProductIdentifier(), vendorIdentifier(), hasVendorIdentifier() -*/ -quint16 QSerialPortInfo::productIdentifier() const -{ - Q_D(const QSerialPortInfo); - return !d ? 0 : d->productIdentifier; -} - -/*! - Returns \c true if there is a valid \c 16-bit vendor number present; otherwise - returns \c false. - - \sa vendorIdentifier(), productIdentifier(), hasProductIdentifier() -*/ -bool QSerialPortInfo::hasVendorIdentifier() const -{ - Q_D(const QSerialPortInfo); - return !d ? false : d->hasVendorIdentifier; -} - -/*! - Returns \c true if there is a valid \c 16-bit product number present; otherwise - returns \c false. - - \sa productIdentifier(), vendorIdentifier(), hasVendorIdentifier() -*/ -bool QSerialPortInfo::hasProductIdentifier() const -{ - Q_D(const QSerialPortInfo); - return !d ? false : d->hasProductIdentifier; -} - -/*! - \fn bool QSerialPortInfo::isNull() const - - Returns whether this QSerialPortInfo object holds a - serial port definition. -*/ - -/*! - \fn QList QSerialPortInfo::standardBaudRates() - - Returns a list of available standard baud rates supported - by the target platform. -*/ -QList QSerialPortInfo::standardBaudRates() -{ - return QSerialPortPrivate::standardBaudRates(); -} - -/*! - \fn QList QSerialPortInfo::availablePorts() - - Returns a list of available serial ports on the system. -*/ - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialportinfo.h b/src/Android/qtandroidserialport/qserialportinfo.h deleted file mode 100644 index efa3abe2018b..000000000000 --- a/src/Android/qtandroidserialport/qserialportinfo.h +++ /dev/null @@ -1,58 +0,0 @@ -// Copyright (C) 2012 Denis Shienkov -// Copyright (C) 2012 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -#include -#include - -#include "qserialportglobal.h" - -QT_BEGIN_NAMESPACE - -class QSerialPort; -class QSerialPortInfoPrivate; - -class Q_SERIALPORT_EXPORT QSerialPortInfo -{ - Q_DECLARE_PRIVATE(QSerialPortInfo) -public: - QSerialPortInfo(); - explicit QSerialPortInfo(const QSerialPort& port); - explicit QSerialPortInfo(const QString& name); - QSerialPortInfo(const QSerialPortInfo& other); - QSerialPortInfo(const QSerialPortInfoPrivate& dd); - ~QSerialPortInfo(); - - QSerialPortInfo& operator=(const QSerialPortInfo& other); - void swap(QSerialPortInfo& other); - - QString portName() const; - QString systemLocation() const; - QString description() const; - QString manufacturer() const; - QString serialNumber() const; - - quint16 vendorIdentifier() const; - quint16 productIdentifier() const; - - bool hasVendorIdentifier() const; - bool hasProductIdentifier() const; - - bool isNull() const; - - static QList standardBaudRates(); - static QList availablePorts(); - -private: - friend QList availablePortsByFiltersOfDevices(bool& ok); - std::unique_ptr d_ptr; -}; - -inline bool QSerialPortInfo::isNull() const -{ - return !d_ptr; -} - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialportinfo_android.cpp b/src/Android/qtandroidserialport/qserialportinfo_android.cpp deleted file mode 100644 index 60788d06e453..000000000000 --- a/src/Android/qtandroidserialport/qserialportinfo_android.cpp +++ /dev/null @@ -1,58 +0,0 @@ -// Copyright (C) 2011-2012 Denis Shienkov -// Copyright (C) 2011 Sergey Belyashov -// Copyright (C) 2012 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#include -#include - -#include - -#include "qserialport_p.h" -#include "qserialportinfo.h" -#include "qserialportinfo_p.h" - -QGC_LOGGING_CATEGORY(QSerialPortInfo_AndroidLog, "Android.AndroidSerialPortInfo") - -QT_BEGIN_NAMESPACE - -QList availablePortsByFiltersOfDevices(bool& ok) -{ - const QList serialPortInfoList = AndroidSerial::availableDevices(); - ok = !serialPortInfoList.isEmpty(); - return serialPortInfoList; -} - -QList availablePortsBySysfs(bool& ok) -{ - ok = false; - return QList(); -} - -QList availablePortsByUdev(bool& ok) -{ - ok = false; - return QList(); -} - -QList QSerialPortInfo::availablePorts() -{ - bool ok = false; - const QList serialPortInfoList = availablePortsByFiltersOfDevices(ok); - return (ok ? serialPortInfoList : QList()); -} - -QString QSerialPortInfoPrivate::portNameToSystemLocation(const QString& source) -{ - return (source.startsWith(QLatin1Char('/')) || source.startsWith(QLatin1String("./")) || - source.startsWith(QLatin1String("../"))) - ? source - : (QLatin1String("/dev/") + source); -} - -QString QSerialPortInfoPrivate::portNameFromSystemLocation(const QString& source) -{ - return source.startsWith(QLatin1String("/dev/")) ? source.mid(5) : source; -} - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qserialportinfo_p.h b/src/Android/qtandroidserialport/qserialportinfo_p.h deleted file mode 100644 index e22c9efc4a7d..000000000000 --- a/src/Android/qtandroidserialport/qserialportinfo_p.h +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright (C) 2011-2012 Denis Shienkov -// Copyright (C) 2017 Sergey Belyashov -// Copyright (C) 2013 Laszlo Papp -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -// -// W A R N I N G -// ------------- -// -// This file is not part of the Qt API. It exists purely as an -// implementation detail. This header file may change from version to -// version without notice, or even be removed. -// -// We mean it. -// - -#include -#include - -QT_BEGIN_NAMESPACE - -class Q_AUTOTEST_EXPORT QSerialPortInfoPrivate -{ -public: - static QString portNameToSystemLocation(const QString &source); - static QString portNameFromSystemLocation(const QString &source); - - QString portName; - QString device; - QString description; - QString manufacturer; - QString serialNumber; - - quint16 vendorIdentifier = 0; - quint16 productIdentifier = 0; - - bool hasVendorIdentifier = false; - bool hasProductIdentifier = false; -}; - -QT_END_NAMESPACE diff --git a/src/Android/qtandroidserialport/qtserialportexports.h b/src/Android/qtandroidserialport/qtserialportexports.h deleted file mode 100644 index 198df1cd6533..000000000000 --- a/src/Android/qtandroidserialport/qtserialportexports.h +++ /dev/null @@ -1,47 +0,0 @@ -// Copyright (C) 2022 The Qt Company Ltd. -// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only - -#pragma once - -#include -#include // Q_SERIALPORT_EXPORT -#include // QT_IF_DEPRECATED_SINCE - -#if defined(QT_SHARED) || !defined(QT_STATIC) -# if defined(QT_BUILD_SERIALPORT_LIB) -# define Q_SERIALPORT_EXPORT Q_DECL_EXPORT -# else -# define Q_SERIALPORT_EXPORT Q_DECL_IMPORT -# endif -#else -# define Q_SERIALPORT_EXPORT -#endif - -#if !defined(QT_BUILD_SERIALPORT_LIB) && !defined(QT_STATIC) -/* outside library -> inline decl + defi */ -/* static builds treat everything as part of the library, so they never inline */ -# define QT_SERIALPORT_INLINE_SINCE(major, minor) inline -# define QT_SERIALPORT_INLINE_IMPL_SINCE(major, minor) 1 -#elif defined(QT_SERIALPORT_BUILD_REMOVED_API) -/* inside library, inside removed_api.cpp: - * keep deprecated API -> non-inline decl; - * remove deprecated API -> inline decl; - * definition is always available */ -# define QT_SERIALPORT_INLINE_SINCE(major, minor) \ - QT_IF_DEPRECATED_SINCE(major, minor, inline, /* not inline */) -# define QT_SERIALPORT_INLINE_IMPL_SINCE(major, minor) 1 -#else -/* inside library, outside removed_api.cpp: - * keep deprecated API -> non-inline decl, no defi; - * remove deprecated API -> inline decl, defi */ -# define QT_SERIALPORT_INLINE_SINCE(major, minor) \ - QT_IF_DEPRECATED_SINCE(major, minor, inline, /* not inline */) -# define QT_SERIALPORT_INLINE_IMPL_SINCE(major, minor) \ - QT_IF_DEPRECATED_SINCE(major, minor, 1, 0) -#endif - -#ifdef QT_SERIALPORT_BUILD_REMOVED_API -# define QT_SERIALPORT_REMOVED_SINCE(major, minor) QT_DEPRECATED_SINCE(major, minor) -#else -# define QT_SERIALPORT_REMOVED_SINCE(major, minor) 0 -#endif diff --git a/src/Android/qtandroidserialport/qtserialportversion.h b/src/Android/qtandroidserialport/qtserialportversion.h deleted file mode 100644 index 3fe2601c46ae..000000000000 --- a/src/Android/qtandroidserialport/qtserialportversion.h +++ /dev/null @@ -1,6 +0,0 @@ -/* This file was generated by syncqt. */ -#pragma once - -#define QTSERIALPORT_VERSION_STR "6.6.3" - -#define QTSERIALPORT_VERSION 0x060603 diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 6464d42359d0..5d80f6b088f2 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -250,7 +250,8 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(bool parametersReady) return; } - if (!QGCSerialPortInfo(*serialLink->port()).isBlackCube()) { + const SerialConfiguration *serialConfig = qobject_cast(serialLink->linkConfiguration().get()); + if (!serialConfig || !QGCSerialPortInfo(serialConfig->portName()).isBlackCube()) { return; } diff --git a/src/Comms/CMakeLists.txt b/src/Comms/CMakeLists.txt index 0748ac4ca126..b69ca0244919 100644 --- a/src/Comms/CMakeLists.txt +++ b/src/Comms/CMakeLists.txt @@ -52,6 +52,8 @@ if(QGC_NO_SERIAL_LINK) else() target_sources(${CMAKE_PROJECT_NAME} PRIVATE + QGCSerialPortAdapter.cc + QGCSerialPortAdapter.h QGCSerialPortInfo.cc QGCSerialPortInfo.h SerialLink.cc diff --git a/src/Comms/LinkManager.cc b/src/Comms/LinkManager.cc index c41f1c29c08f..aff3da449b7c 100644 --- a/src/Comms/LinkManager.cc +++ b/src/Comms/LinkManager.cc @@ -21,6 +21,7 @@ #include "SerialLink.h" #include "GPSManager.h" #include "GPSRtk.h" +#include "QGCSerialPortAdapter.h" #endif #ifdef QT_DEBUG @@ -762,7 +763,8 @@ void LinkManager::_addSerialAutoConnectLink() if (portInfo.systemLocation().trimmed() != _nmeaDeviceName) { _nmeaDeviceName = portInfo.systemLocation().trimmed(); qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName; - QSerialPort* newPort = new QSerialPort(portInfo, this); + auto* newPort = new QGCSerialPortAdapter(this); + newPort->setPortName(portInfo.systemLocation()); _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt(); newPort->setBaudRate(static_cast(_nmeaBaud)); qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud; diff --git a/src/Comms/LinkManager.h b/src/Comms/LinkManager.h index 747874365a9c..462dc36078a9 100644 --- a/src/Comms/LinkManager.h +++ b/src/Comms/LinkManager.h @@ -18,6 +18,7 @@ class AutoConnectSettings; class LogReplayLink; class MAVLinkProtocol; class QmlObjectListModel; +class QGCSerialPortAdapter; class QTimer; class SerialLink; class UDPConfiguration; @@ -183,7 +184,7 @@ private slots: QString _autoConnectRTKPort; QString _nmeaDeviceName; uint32_t _nmeaBaud = 0; - QSerialPort *_nmeaPort = nullptr; + QGCSerialPortAdapter *_nmeaPort = nullptr; #endif // QGC_NO_SERIAL_LINK // NMEA UDP is network-only; available regardless of QGC_NO_SERIAL_LINK. diff --git a/src/Comms/QGCSerialPortAdapter.cc b/src/Comms/QGCSerialPortAdapter.cc new file mode 100644 index 000000000000..e2d15f27b400 --- /dev/null +++ b/src/Comms/QGCSerialPortAdapter.cc @@ -0,0 +1,316 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#include "QGCSerialPortAdapter.h" + +#include "QGCAndroidSerialPort.h" + +#ifndef Q_OS_ANDROID +#include +#endif + +// On host, the adapter normally wraps QSerialPort. Tests can call +// setForceAndroidBackendForTests(true) to make it wrap QGCAndroidSerialPort instead +// (paired with QGCAndroidSerialPortFactory::setEngineFactory(mock)) — that's how +// SerialLink integration tests exercise the Android code path without a device. +namespace { +bool& forceAndroidBackend() +{ + static bool flag = false; + return flag; +} +} // namespace + +void QGCSerialPortAdapter::setForceAndroidBackendForTests(bool force) +{ + forceAndroidBackend() = force; +} + +bool QGCSerialPortAdapter::forceAndroidBackendForTests() +{ + return forceAndroidBackend(); +} + +// ============================================================================ +// Strategy interface + per-backend implementations. +// +// Replaces the prior Pimpl-with-ifdef-per-method pattern. The adapter now calls +// exactly one virtual per operation; both concrete types (HostSerialBackend on +// !Q_OS_ANDROID, AndroidSerialBackend everywhere) translate to their underlying +// port. The only platform branching that remains is in makeBackend() — the +// factory that picks the concrete type at construction. +// +// Modeled on Qt's QNetworkAccessBackend / QNetworkAccessBackendFactory split +// (see qtbase/src/network/access/qnetworkaccessbackend_p.h). +// ============================================================================ + +class QGCSerialBackend +{ +public: + QGCSerialBackend() = default; + virtual ~QGCSerialBackend() = default; + Q_DISABLE_COPY_MOVE(QGCSerialBackend) + + virtual QIODevice *device() = 0; + virtual void setPortName(const QString &name) = 0; + virtual QString portName() const = 0; + virtual bool flush() = 0; + virtual void setWriteBufferSize(qint64 size) = 0; + virtual void clearError() = 0; + virtual QGCSerialPortAdapter::Error error() const = 0; + virtual bool setBaudRate(qint32 baud) = 0; + virtual bool setDataBits(int bits) = 0; + virtual bool setParity(int parity) = 0; + virtual bool setStopBits(int bits) = 0; + virtual bool setFlowControl(int flow) = 0; + virtual bool setSerialParameters(qint32 baud, int dataBits, int stopBits, int parity) = 0; + virtual bool setDataTerminalReady(bool on) = 0; + + // Wires the platform-specific errorOccurred signal so the adapter emits + // errorOccurred(Error) with a mapped value. Lives on the backend because + // the source-signal type differs per backend. + virtual void connectErrorSignal(QGCSerialPortAdapter *adapter) = 0; +}; + +namespace { + +QGCDataBits intToDataBits(int v) +{ + switch (v) { + case 5: return QGCDataBits::Data5; + case 6: return QGCDataBits::Data6; + case 7: return QGCDataBits::Data7; + default: return QGCDataBits::Data8; + } +} + +QGCParity intToParity(int v) +{ + // QSerialPort::Parity values: NoParity=0, EvenParity=2, OddParity=3, + // SpaceParity=4, MarkParity=5. (Not 0..4 — gap at 1.) + switch (v) { + case 0: return QGCParity::None; + case 2: return QGCParity::Even; + case 3: return QGCParity::Odd; + case 4: return QGCParity::Space; + case 5: return QGCParity::Mark; + default: return QGCParity::None; + } +} + +QGCStopBits intToStopBits(int v) +{ + switch (v) { + case 2: return QGCStopBits::Two; + case 3: return QGCStopBits::OneAndHalf; + default: return QGCStopBits::One; + } +} + +QGCFlowControl intToFlowControl(int v) +{ + switch (v) { + case 1: return QGCFlowControl::HardwareRtsCts; + case 2: return QGCFlowControl::SoftwareXonXoff; + default: return QGCFlowControl::None; + } +} + +QGCSerialPortAdapter::Error mapAndroidError(QGCSerialPortError e) +{ + switch (e) { + case QGCSerialPortError::NoError: return QGCSerialPortAdapter::NoError; + case QGCSerialPortError::ResourceUnavailable: return QGCSerialPortAdapter::ResourceError; + case QGCSerialPortError::PermissionDenied: return QGCSerialPortAdapter::PermissionError; + case QGCSerialPortError::Timeout: return QGCSerialPortAdapter::TimeoutError; + default: return QGCSerialPortAdapter::OtherError; + } +} + +#ifndef Q_OS_ANDROID +QGCSerialPortAdapter::Error mapHostError(QSerialPort::SerialPortError e) +{ + switch (e) { + case QSerialPort::NoError: return QGCSerialPortAdapter::NoError; + case QSerialPort::ResourceError: return QGCSerialPortAdapter::ResourceError; + case QSerialPort::PermissionError: return QGCSerialPortAdapter::PermissionError; + case QSerialPort::TimeoutError: return QGCSerialPortAdapter::TimeoutError; + default: return QGCSerialPortAdapter::OtherError; + } +} +#endif + +class AndroidSerialBackend final : public QGCSerialBackend +{ +public: + explicit AndroidSerialBackend(QObject *parent) : _port(new QGCAndroidSerialPort(parent)) {} + + QIODevice *device() override { return _port; } + void setPortName(const QString &name) override { _port->setSystemLocation(name); } + QString portName() const override { return _port->portName(); } + bool flush() override { return _port->flush(); } + void setWriteBufferSize(qint64 size) override { _port->setWriteBufferSize(size); } + void clearError() override { _port->clearError(); } + QGCSerialPortAdapter::Error error() const override { return mapAndroidError(_port->error()); } + bool setBaudRate(qint32 baud) override { return _port->setBaudRate(baud); } + bool setDataBits(int bits) override { return _port->setDataBits(intToDataBits(bits)); } + bool setParity(int parity) override { return _port->setParity(intToParity(parity)); } + bool setStopBits(int bits) override { return _port->setStopBits(intToStopBits(bits)); } + bool setFlowControl(int flow) override { return _port->setFlowControl(intToFlowControl(flow)); } + bool setSerialParameters(qint32 baud, int dataBits, int stopBits, int parity) override + { + return _port->setSerialParameters(baud, intToDataBits(dataBits), + intToStopBits(stopBits), intToParity(parity)); + } + bool setDataTerminalReady(bool on) override { return _port->setDataTerminalReady(on); } + + void connectErrorSignal(QGCSerialPortAdapter *adapter) override + { + QObject::connect(_port, &QGCAndroidSerialPort::errorOccurred, adapter, + [adapter](QGCSerialPortError e) { emit adapter->errorOccurred(mapAndroidError(e)); }); + } + +private: + QGCAndroidSerialPort *const _port; +}; + +#ifndef Q_OS_ANDROID +class HostSerialBackend final : public QGCSerialBackend +{ +public: + explicit HostSerialBackend(QObject *parent) : _port(new QSerialPort(parent)) {} + + QIODevice *device() override { return _port; } + void setPortName(const QString &name) override { _port->setPortName(name); } + QString portName() const override { return _port->portName(); } + bool flush() override { return _port->flush(); } + void setWriteBufferSize(qint64 size) override { _port->setWriteBufferSize(size); } + void clearError() override { _port->clearError(); } + QGCSerialPortAdapter::Error error() const override { return mapHostError(_port->error()); } + bool setBaudRate(qint32 baud) override { return _port->setBaudRate(baud); } + bool setDataBits(int bits) override { return _port->setDataBits(static_cast(bits)); } + bool setParity(int parity) override { return _port->setParity(static_cast(parity)); } + bool setStopBits(int bits) override { return _port->setStopBits(static_cast(bits)); } + bool setFlowControl(int flow) override { return _port->setFlowControl(static_cast(flow)); } + // QSerialPort has no batched setter — call the four in sequence. Each goes + // straight to termios on Linux/macOS / SetCommState on Windows; no JNI hop. + bool setSerialParameters(qint32 baud, int dataBits, int stopBits, int parity) override + { + const bool ok1 = _port->setBaudRate(baud); + const bool ok2 = _port->setDataBits(static_cast(dataBits)); + const bool ok3 = _port->setStopBits(static_cast(stopBits)); + const bool ok4 = _port->setParity(static_cast(parity)); + return ok1 && ok2 && ok3 && ok4; + } + bool setDataTerminalReady(bool on) override { return _port->setDataTerminalReady(on); } + + void connectErrorSignal(QGCSerialPortAdapter *adapter) override + { + QObject::connect(_port, &QSerialPort::errorOccurred, adapter, + [adapter](QSerialPort::SerialPortError e) { emit adapter->errorOccurred(mapHostError(e)); }); + } + +private: + QSerialPort *const _port; +}; +#endif + +// Only platform-conditional path that remains: picking the concrete backend. +std::unique_ptr makeBackend(QObject *parent) +{ +#ifdef Q_OS_ANDROID + return std::make_unique(parent); +#else + if (QGCSerialPortAdapter::forceAndroidBackendForTests()) { + return std::make_unique(parent); + } + return std::make_unique(parent); +#endif +} + +} // namespace + +QGCSerialPortAdapter::QGCSerialPortAdapter(QObject *parent) + : QIODevice(parent) + , _backend(makeBackend(this)) +{ + QIODevice *const backend = _backend->device(); + // Forward readyRead/aboutToClose from the inner device. readyRead drives + // consumers' read() calls which route through readData() → backend->read(). + connect(backend, &QIODevice::readyRead, this, &QIODevice::readyRead); + connect(backend, &QIODevice::bytesWritten, this, &QIODevice::bytesWritten); + // Inner can self-close on resource error; mirror that into the adapter's + // QIODevice state so isOpen() reflects reality. aboutToClose fires BEFORE + // the inner tears down, so calling QIODevice::close() here keeps the + // forwarded signal observable to consumers. + connect(backend, &QIODevice::aboutToClose, this, [this]() { + if (QIODevice::isOpen()) { + QIODevice::close(); + } + emit aboutToClose(); + }); + _backend->connectErrorSignal(this); +} + +QGCSerialPortAdapter::~QGCSerialPortAdapter() = default; + +void QGCSerialPortAdapter::setPortName(const QString &name) { _backend->setPortName(name); } +QString QGCSerialPortAdapter::portName() const { return _backend->portName(); } + +bool QGCSerialPortAdapter::open(QIODevice::OpenMode mode) +{ + if (!_backend->device()->open(mode)) { + setErrorString(_backend->device()->errorString()); + return false; + } + // Mark the adapter open so QIODevice's read/write plumbing accepts calls. + QIODevice::open(mode); + return true; +} + +void QGCSerialPortAdapter::close() +{ + _backend->device()->close(); + QIODevice::close(); +} + +// QIODevice's bytesAvailable returns its own buffer size; we keep adapter buffer +// empty (we delegate readData directly) so forward to the inner backend. +qint64 QGCSerialPortAdapter::bytesAvailable() const +{ + return QIODevice::bytesAvailable() + _backend->device()->bytesAvailable(); +} + +qint64 QGCSerialPortAdapter::bytesToWrite() const { return _backend->device()->bytesToWrite(); } +bool QGCSerialPortAdapter::waitForReadyRead(int m) { return _backend->device()->waitForReadyRead(m); } +bool QGCSerialPortAdapter::waitForBytesWritten(int m){ return _backend->device()->waitForBytesWritten(m); } +bool QGCSerialPortAdapter::flush() { return _backend->flush(); } + +qint64 QGCSerialPortAdapter::readData(char *data, qint64 maxSize) +{ + return _backend->device()->read(data, maxSize); +} + +qint64 QGCSerialPortAdapter::writeData(const char *data, qint64 size) +{ + return _backend->device()->write(data, size); +} + +void QGCSerialPortAdapter::setWriteBufferSize(qint64 size) { _backend->setWriteBufferSize(size); } +void QGCSerialPortAdapter::clearError() { _backend->clearError(); } +QGCSerialPortAdapter::Error QGCSerialPortAdapter::error() const { return _backend->error(); } + +bool QGCSerialPortAdapter::setBaudRate(qint32 baud) { return _backend->setBaudRate(baud); } +bool QGCSerialPortAdapter::setDataBits(int bits) { return _backend->setDataBits(bits); } +bool QGCSerialPortAdapter::setParity(int parity) { return _backend->setParity(parity); } +bool QGCSerialPortAdapter::setStopBits(int bits) { return _backend->setStopBits(bits); } +bool QGCSerialPortAdapter::setFlowControl(int flow) { return _backend->setFlowControl(flow); } + +bool QGCSerialPortAdapter::setSerialParameters(qint32 baud, int dataBits, int stopBits, int parity) +{ + return _backend->setSerialParameters(baud, dataBits, stopBits, parity); +} + +bool QGCSerialPortAdapter::setDataTerminalReady(bool on) +{ + return _backend->device()->isOpen() && _backend->setDataTerminalReady(on); +} diff --git a/src/Comms/QGCSerialPortAdapter.h b/src/Comms/QGCSerialPortAdapter.h new file mode 100644 index 000000000000..7b60dca5323f --- /dev/null +++ b/src/Comms/QGCSerialPortAdapter.h @@ -0,0 +1,134 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#pragma once + +// +// QGCSerialPortAdapter — single serial-port type used across QGC. +// +// Inherits QIODevice so consumers (SerialLink, Bootloader, GPSProvider, NMEA) +// can do polymorphic read/write/wait* and pass instances to APIs that take +// QIODevice* (e.g. setNmeaSourceDevice). Owns one of: +// - host: QSerialPort +// - Android: QGCAndroidSerialPort +// The Q_OS_ANDROID branch lives entirely inside the .cc — consumers never +// include qserialport.h or qserialport_android.cpp. +// +// Enums mirror QSerialPort::* numeric values exactly so existing call sites +// that used QSerialPort::Baud115200 / Data8 / NoParity migrate by symbol +// substitution; no value changes. +// + +#include +#include +#include +#include + +#include + +class QGCSerialBackend; + +class QGCSerialPortAdapter : public QIODevice +{ + Q_OBJECT + +public: + // Mirrors QSerialPort::SerialPortError values that SerialWorker switches on. + // Full enum has more entries; we collapse the rest into OtherError because + // SerialWorker's default branch already treats them uniformly. + enum Error { + NoError = 0, + ResourceError = 9, + PermissionError = 2, + TimeoutError = 12, // matches QSerialPort::TimeoutError + OtherError = 99, + }; + Q_ENUM(Error) + + // Numeric values match QSerialPort::DataBits. + enum DataBits { Data5 = 5, Data6 = 6, Data7 = 7, Data8 = 8 }; + Q_ENUM(DataBits) + + // Numeric values match QSerialPort::Parity — note the gap at 1 (no value). + enum Parity { + NoParity = 0, + EvenParity = 2, + OddParity = 3, + SpaceParity = 4, + MarkParity = 5, + }; + Q_ENUM(Parity) + + // Numeric values match QSerialPort::StopBits. + enum StopBits { OneStop = 1, OneAndHalfStop = 3, TwoStop = 2 }; + Q_ENUM(StopBits) + + // Numeric values match QSerialPort::FlowControl. + enum FlowControl { + NoFlowControl = 0, + HardwareControl = 1, + SoftwareControl = 2, + }; + Q_ENUM(FlowControl) + + // Common baud rates — numeric values are the wire baud rates themselves + // (also match QSerialPort::BaudRate where they exist). + enum BaudRate { + Baud1200 = 1200, + Baud2400 = 2400, + Baud4800 = 4800, + Baud9600 = 9600, + Baud19200 = 19200, + Baud38400 = 38400, + Baud57600 = 57600, + Baud115200 = 115200, + }; + Q_ENUM(BaudRate) + + explicit QGCSerialPortAdapter(QObject *parent = nullptr); + ~QGCSerialPortAdapter() override; + + // Test-only override: forces the adapter to use the QGCAndroidSerialPort backend + // even on host builds. Set BEFORE constructing any QGCSerialPortAdapter instances. + static void setForceAndroidBackendForTests(bool force); + static bool forceAndroidBackendForTests(); + + void setPortName(const QString &name); + QString portName() const; + + bool open(QIODevice::OpenMode mode) override; + void close() override; + + qint64 bytesAvailable() const override; + qint64 bytesToWrite() const override; + bool waitForReadyRead(int msecs) override; + bool waitForBytesWritten(int msecs) override; + bool flush(); + + void setWriteBufferSize(qint64 size); + Error error() const; + void clearError(); + + bool setBaudRate(qint32 baud); + bool setDataBits(int bits); // accepts DataBits enum or raw int + bool setParity(int parity); // accepts Parity enum or raw int + bool setStopBits(int bits); // accepts StopBits enum or raw int + bool setFlowControl(int flow); // accepts FlowControl enum or raw int + // Batched setter — Android collapses 4 JNI hops into 1; host falls through + // to the four QSerialPort setters (Qt has no batched API). + bool setSerialParameters(qint32 baud, int dataBits, int stopBits, int parity); + bool setDataTerminalReady(bool on); + +signals: + void errorOccurred(QGCSerialPortAdapter::Error error); + +protected: + qint64 readData(char *data, qint64 maxSize) override; + qint64 writeData(const char *data, qint64 size) override; + +private: + // Strategy-pattern backend. Concrete types (HostSerialBackend / AndroidSerialBackend) + // live entirely in the .cc — the adapter calls only the virtual interface, so + // platform branching collapses to the single factory call in the constructor. + // Pattern reference: Qt's QNetworkAccessBackend (qtbase/src/network/access/). + std::unique_ptr _backend; +}; diff --git a/src/Comms/QGCSerialPortInfo.cc b/src/Comms/QGCSerialPortInfo.cc index 01f5f866880e..5d66632f2684 100644 --- a/src/Comms/QGCSerialPortInfo.cc +++ b/src/Comms/QGCSerialPortInfo.cc @@ -8,6 +8,12 @@ #include #include +#ifdef Q_OS_ANDROID +#include "AndroidSerial.h" +#else +#include +#endif + QGC_LOGGING_CATEGORY(QGCSerialPortInfoLog, "Comms.QGCSerialPortInfo") bool QGCSerialPortInfo::_jsonLoaded = false; @@ -16,22 +22,56 @@ QList QGCSerialPortInfo::_boardInfoList; QList QGCSerialPortInfo::_boardDescriptionFallbackList; QList QGCSerialPortInfo::_boardManufacturerFallbackList; -QGCSerialPortInfo::QGCSerialPortInfo() - : QSerialPortInfo() +// Matches Qt SerialPort's internal kStandardBaudRates (see qserialport_unix.cpp / +// qserialport_win.cpp). Platform-independent literal — defined here so callers +// don't pull in QtSerialPort just to enumerate baud rates. +QList QGCSerialPortInfo::standardBaudRates() +{ + static constexpr qint32 kRates[] = { + 50, 75, 110, 134, 150, 200, 300, 600, 1200, 1800, + 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 460800, 500000, + 576000, 921600, 1000000, 1152000, 1500000, 2000000, 2500000, 3000000, 3500000, 4000000, + }; + return QList(std::begin(kRates), std::end(kRates)); +} + +QGCSerialPortInfo::QGCSerialPortInfo() = default; +QGCSerialPortInfo::QGCSerialPortInfo(const QGCSerialPortInfo &) = default; +QGCSerialPortInfo::QGCSerialPortInfo(QGCSerialPortInfo &&) noexcept = default; +QGCSerialPortInfo &QGCSerialPortInfo::operator=(const QGCSerialPortInfo &) = default; +QGCSerialPortInfo &QGCSerialPortInfo::operator=(QGCSerialPortInfo &&) noexcept = default; +QGCSerialPortInfo::~QGCSerialPortInfo() = default; + +QGCSerialPortInfo::QGCSerialPortInfo(Data data) + : _data(std::move(data)) { - qCDebug(QGCSerialPortInfoLog) << this; } -QGCSerialPortInfo::QGCSerialPortInfo(const QSerialPort &port) - : QSerialPortInfo(port) +QGCSerialPortInfo::QGCSerialPortInfo(const QString &name) { - qCDebug(QGCSerialPortInfoLog) << this; + const QList ports = availablePorts(); + for (const QGCSerialPortInfo &info : ports) { + if (info.portName() == name || info.systemLocation() == name) { + _data = info._data; + return; + } + } } -QGCSerialPortInfo::~QGCSerialPortInfo() +#ifndef Q_OS_ANDROID +QGCSerialPortInfo::QGCSerialPortInfo(const QSerialPortInfo &info) { - qCDebug(QGCSerialPortInfoLog) << this; + _data.portName = info.portName(); + _data.systemLocation = info.systemLocation(); + _data.description = info.description(); + _data.manufacturer = info.manufacturer(); + _data.serialNumber = info.serialNumber(); + _data.vendorIdentifier = info.vendorIdentifier(); + _data.productIdentifier = info.productIdentifier(); + _data.hasVendorIdentifier = info.hasVendorIdentifier(); + _data.hasProductIdentifier= info.hasProductIdentifier(); } +#endif bool QGCSerialPortInfo::_loadJsonData() { @@ -258,15 +298,24 @@ QList QGCSerialPortInfo::availablePorts() { QList list; +#ifdef Q_OS_ANDROID + const QList androidPorts = AndroidSerial::availableDevices(); + for (const QGCSerialPortInfo &portInfo : androidPorts) { + if (isSystemPort(portInfo)) { + continue; + } + list << portInfo; + } +#else const QList availablePorts = QSerialPortInfo::availablePorts(); for (const QSerialPortInfo &portInfo : availablePorts) { - if (isSystemPort(portInfo)) { + QGCSerialPortInfo qgcPortInfo(portInfo); + if (isSystemPort(qgcPortInfo)) { continue; } - - const QGCSerialPortInfo *const qgcPortInfo = reinterpret_cast(&portInfo); - list << *qgcPortInfo; + list << qgcPortInfo; } +#endif return list; } @@ -287,7 +336,7 @@ bool QGCSerialPortInfo::isBlackCube() const return description().contains(QStringLiteral("CubeBlack")); } -bool QGCSerialPortInfo::isSystemPort(const QSerialPortInfo &port) +bool QGCSerialPortInfo::isSystemPort(const QGCSerialPortInfo &port) { #ifdef Q_OS_MACOS static const QList systemPortLocations = { diff --git a/src/Comms/QGCSerialPortInfo.h b/src/Comms/QGCSerialPortInfo.h index 2a006aa0ab25..8318112e98dc 100644 --- a/src/Comms/QGCSerialPortInfo.h +++ b/src/Comms/QGCSerialPortInfo.h @@ -1,26 +1,50 @@ #pragma once +#include +#include #include +#include #include -#ifdef Q_OS_ANDROID - #include "qserialportinfo.h" -#else - #include -#endif -class QGCSerialPortInfoTest; +QT_BEGIN_NAMESPACE +class QSerialPortInfo; +QT_END_NAMESPACE -/// \brief QGC's version of Qt QSerialPortInfo. It provides additional information about board types -/// that QGC cares about. +class QGCSerialPortInfoTest; -class QGCSerialPortInfo : public QSerialPortInfo +/// \brief QGC's standalone port descriptor. On host this is populated from Qt's QSerialPortInfo; +/// on Android it is populated directly from the Java USB enumeration (see AndroidSerial.cc). +/// Standalone (i.e. not derived from QSerialPortInfo) so the Android build can avoid the +/// vendored qserialportinfo private API. +class QGCSerialPortInfo { friend class QGCSerialPortInfoTest; public: + struct Data { + QString portName; + QString systemLocation; + QString description; + QString manufacturer; + QString serialNumber; + quint16 vendorIdentifier = 0; + quint16 productIdentifier = 0; + bool hasVendorIdentifier = false; + bool hasProductIdentifier = false; + }; + QGCSerialPortInfo(); - explicit QGCSerialPortInfo(const QSerialPort &port); + QGCSerialPortInfo(const QGCSerialPortInfo &other); + QGCSerialPortInfo(QGCSerialPortInfo &&other) noexcept; + explicit QGCSerialPortInfo(const QString &name); + explicit QGCSerialPortInfo(Data data); +#ifndef Q_OS_ANDROID + explicit QGCSerialPortInfo(const QSerialPortInfo &info); +#endif ~QGCSerialPortInfo(); + QGCSerialPortInfo &operator=(const QGCSerialPortInfo &other); + QGCSerialPortInfo &operator=(QGCSerialPortInfo &&other) noexcept; + enum BoardType_t { BoardTypePixhawk = 0, BoardTypeSiKRadio, @@ -29,6 +53,17 @@ class QGCSerialPortInfo : public QSerialPortInfo BoardTypeUnknown }; + QString portName() const { return _data.portName; } + QString systemLocation() const { return _data.systemLocation; } + QString description() const { return _data.description; } + QString manufacturer() const { return _data.manufacturer; } + QString serialNumber() const { return _data.serialNumber; } + quint16 vendorIdentifier() const { return _data.vendorIdentifier; } + quint16 productIdentifier()const { return _data.productIdentifier; } + bool hasVendorIdentifier() const { return _data.hasVendorIdentifier; } + bool hasProductIdentifier() const { return _data.hasProductIdentifier; } + bool isNull() const { return _data.portName.isEmpty() && _data.systemLocation.isEmpty(); } + bool getBoardInfo(BoardType_t &boardType, QString &name) const; /// @return true: we can flash this board type @@ -42,11 +77,15 @@ class QGCSerialPortInfo : public QSerialPortInfo /// Known operating system peripherals that are NEVER a peripheral that we should connect to. /// @return true: Port is a system port and not an autopilot - static bool isSystemPort(const QSerialPortInfo &port); + static bool isSystemPort(const QGCSerialPortInfo &port); - /// Override of QSerialPortInfo::availablePorts static QList availablePorts(); + /// Platform-independent table of standard baud rates (matches Qt SerialPort + /// internal kStandardBaudRates). Provided locally so callers don't need to + /// pull in QtSerialPort/QSerialPortInfo just for this constant. + static QList standardBaudRates(); + private: struct BoardClassString2BoardType_t { const QString classString; @@ -86,5 +125,7 @@ class QGCSerialPortInfo : public QSerialPortInfo static constexpr const char *_jsonNameKey = "name"; static constexpr const char *_jsonRegExpKey = "regExp"; static constexpr const char *_jsonAndroidOnlyKey = "androidOnly"; + + Data _data; }; Q_DECLARE_METATYPE(QGCSerialPortInfo) diff --git a/src/Comms/SerialLink.cc b/src/Comms/SerialLink.cc index 4df76c24dcff..0e3e6ba63f1a 100644 --- a/src/Comms/SerialLink.cc +++ b/src/Comms/SerialLink.cc @@ -1,6 +1,7 @@ #include "SerialLink.h" #include "QGCLoggingCategory.h" #include "QGCSerialPortInfo.h" +#include "QGCSerialPortAdapter.h" #include #include #include @@ -71,13 +72,14 @@ void SerialConfiguration::loadSettings(QSettings &settings, const QString &root) settings.beginGroup(root); setBaud(settings.value("baud", _baud).toInt()); - setDataBits(static_cast(settings.value("dataBits", _dataBits).toInt())); - setFlowControl(static_cast(settings.value("flowControl", _flowControl).toInt())); - setStopBits(static_cast(settings.value("stopBits", _stopBits).toInt())); - setParity(static_cast(settings.value("parity", _parity).toInt())); + setDataBits(settings.value("dataBits", _dataBits).toInt()); + setFlowControl(settings.value("flowControl", _flowControl).toInt()); + setStopBits(settings.value("stopBits", _stopBits).toInt()); + setParity(settings.value("parity", _parity).toInt()); setPortName(settings.value("portName", _portName).toString()); setPortDisplayName(settings.value("portDisplayName", _portDisplayName).toString()); setdtrForceLow(settings.value("dtrForceLow", _dtrForceLow).toBool()); + setUsbDirect(settings.value("usbDirect", _usbDirect).toBool()); settings.endGroup(); } @@ -94,6 +96,7 @@ void SerialConfiguration::saveSettings(QSettings &settings, const QString &root) settings.setValue("portName", _portName); settings.setValue("portDisplayName", _portDisplayName); settings.setValue("dtrForceLow", _dtrForceLow); + settings.setValue("usbDirect", _usbDirect); settings.endGroup(); } @@ -145,7 +148,7 @@ QStringList SerialConfiguration::supportedBaudRates() 921600, }; - const QList activeSupportedBaudRates = QSerialPortInfo::standardBaudRates(); + const QList activeSupportedBaudRates = QGCSerialPortInfo::standardBaudRates(); QSet mergedBaudRateSet(kDefaultSupportedBaudRates.constBegin(), kDefaultSupportedBaudRates.constEnd()); (void) mergedBaudRateSet.unite(QSet(activeSupportedBaudRates.constBegin(), activeSupportedBaudRates.constEnd())); @@ -164,8 +167,8 @@ QStringList SerialConfiguration::supportedBaudRates() QString SerialConfiguration::cleanPortDisplayName(const QString &name) { - const QList availablePorts = QSerialPortInfo::availablePorts(); - for (const QSerialPortInfo &portInfo : availablePorts) { + const QList availablePorts = QGCSerialPortInfo::availablePorts(); + for (const QGCSerialPortInfo &portInfo : availablePorts) { if (portInfo.systemLocation() == name) { return portInfo.portName(); } @@ -182,7 +185,7 @@ SerialWorker::SerialWorker(const SerialConfiguration *config, QObject *parent) { qCDebug(SerialLinkLog) << this; - (void) qRegisterMetaType("QSerialPort::SerialPortError"); + (void) qRegisterMetaType("QGCSerialPortAdapter::Error"); } SerialWorker::~SerialWorker() @@ -200,20 +203,16 @@ bool SerialWorker::isConnected() const void SerialWorker::setupPort() { if (!_port) { - _port = new QSerialPort(this); + _port = new QGCSerialPortAdapter(this); } if (!_timer) { _timer = new QTimer(this); } - (void) connect(_port, &QSerialPort::aboutToClose, this, &SerialWorker::_onPortDisconnected); - (void) connect(_port, &QSerialPort::readyRead, this, &SerialWorker::_onPortReadyRead); - (void) connect(_port, &QSerialPort::errorOccurred, this, &SerialWorker::_onPortErrorOccurred); - - /* if (SerialLinkLog().isDebugEnabled()) { - (void) connect(_port, &QSerialPort::bytesWritten, this, &SerialWorker::_onPortBytesWritten); - } */ + (void) connect(_port, &QGCSerialPortAdapter::aboutToClose, this, &SerialWorker::_onPortDisconnected); + (void) connect(_port, &QGCSerialPortAdapter::readyRead, this, &SerialWorker::_onPortReadyRead); + (void) connect(_port, &QGCSerialPortAdapter::errorOccurred, this, &SerialWorker::_onPortErrorOccurred); (void) connect(_timer, &QTimer::timeout, this, &SerialWorker::_checkPortAvailability); } @@ -227,7 +226,7 @@ void SerialWorker::connectToPort() _port->setPortName(_serialConfig->portName()); - const QGCSerialPortInfo portInfo(*_port); + const QGCSerialPortInfo portInfo(_serialConfig->portName()); if (portInfo.isBootloader()) { qCWarning(SerialLinkLog) << "Not connecting to bootloader" << _port->portName(); emit errorOccurred(tr("Not connecting to a bootloader")); @@ -238,11 +237,17 @@ void SerialWorker::connectToPort() _errorEmitted = false; qCDebug(SerialLinkLog) << "Attempting to open port" << _port->portName(); + // 2 MB soft cap on the internal write buffer. Past this, writeData() returns -1 + WriteError + // instead of letting the buffer grow unboundedly under sustained overload (no in-band + // backpressure exists on the JNI write path). With the AsyncUsbWritePump in place this is a + // defensive net rather than the operative limit — typical Stage 2 traffic peaks at ~18 KB — + // but it's still load-bearing for genuine pathological flooders (CDC drain caps ~200 KB/s). + _port->setWriteBufferSize(2 * 1024 * 1024); if (!_port->open(QIODevice::ReadWrite)) { qCWarning(SerialLinkLog) << "Opening port" << _port->portName() << "failed:" << _port->errorString(); // If auto-connect is enabled, we don't want to emit an error for PermissionError from devices already in use - if (!_errorEmitted && (!_serialConfig->isAutoConnect() || _port->error() != QSerialPort::PermissionError)) { + if (!_errorEmitted && (!_serialConfig->isAutoConnect() || _port->error() != QGCSerialPortAdapter::PermissionError)) { emit errorOccurred(tr("Could not open port: %1").arg(_port->errorString())); _errorEmitted = true; } @@ -270,17 +275,17 @@ void SerialWorker::disconnectFromPort() void SerialWorker::writeData(const QByteArray &data) { if (data.isEmpty()) { - emit errorOccurred(tr("Data to Send is Empty")); + _emitErrorOnce(tr("Data to Send is Empty")); return; } if (!isConnected()) { - emit errorOccurred(tr("Port is not Connected")); + _emitErrorOnce(tr("Port is not Connected")); return; } if (!_port->isWritable()) { - emit errorOccurred(tr("Port is not Writable")); + _emitErrorOnce(tr("Port is not Writable")); return; } @@ -288,10 +293,10 @@ void SerialWorker::writeData(const QByteArray &data) while (totalBytesWritten < data.size()) { const qint64 bytesWritten = _port->write(data.constData() + totalBytesWritten, data.size() - totalBytesWritten); if (bytesWritten == -1) { - emit errorOccurred(tr("Could Not Send Data - Write Failed: %1").arg(_port->errorString())); + _emitErrorOnce(tr("Could Not Send Data - Write Failed: %1").arg(_port->errorString())); return; } else if (bytesWritten == 0) { - emit errorOccurred(tr("Could Not Send Data - Write Returned 0 Bytes")); + _emitErrorOnce(tr("Could Not Send Data - Write Returned 0 Bytes")); return; } totalBytesWritten += bytesWritten; @@ -301,16 +306,29 @@ void SerialWorker::writeData(const QByteArray &data) emit dataSent(sent); } +void SerialWorker::_emitErrorOnce(const QString &errorString) +{ + // Gate all error emissions so a sustained write-cap or disconnected-port + // condition cannot flood the UI thread with showAppMessage modals at + // burst-rate. Reset on (re)connect/disconnect via _onPortConnected / + // _onPortDisconnected. + if (_errorEmitted) { + return; + } + _errorEmitted = true; + emit errorOccurred(errorString); +} + void SerialWorker::_onPortConnected() { qCDebug(SerialLinkLog) << "Port connected:" << _port->portName(); _port->setDataTerminalReady(_serialConfig->dtrForceLow() ? false : true); - _port->setBaudRate(_serialConfig->baud()); - _port->setDataBits(static_cast(_serialConfig->dataBits())); - _port->setFlowControl(static_cast(_serialConfig->flowControl())); - _port->setStopBits(static_cast(_serialConfig->stopBits())); - _port->setParity(static_cast(_serialConfig->parity())); + _port->setSerialParameters(_serialConfig->baud(), + _serialConfig->dataBits(), + _serialConfig->stopBits(), + _serialConfig->parity()); + _port->setFlowControl(_serialConfig->flowControl()); if (_timer) { _timer->start(CONNECT_TIMEOUT_MS); @@ -336,28 +354,21 @@ void SerialWorker::_onPortReadyRead() { const QByteArray data = _port->readAll(); if (!data.isEmpty()) { - // qCDebug(SerialLinkLog) << data.size(); emit dataReceived(data); } } -void SerialWorker::_onPortBytesWritten(qint64 bytes) const -{ - qCDebug(SerialLinkLog) << _port->portName() << "Wrote" << bytes << "bytes"; -} - -void SerialWorker::_onPortErrorOccurred(QSerialPort::SerialPortError portError) +void SerialWorker::_onPortErrorOccurred(QGCSerialPortAdapter::Error portError) { switch (portError) { - case QSerialPort::NoError: - qCDebug(SerialLinkLog) << "About to open port" << _port->portName(); + case QGCSerialPortAdapter::NoError: return; - case QSerialPort::ResourceError: + case QGCSerialPortAdapter::ResourceError: // We get this when a usb cable is unplugged - close port to allow reconnection qCDebug(SerialLinkLog) << "Resource error (likely USB disconnect):" << _port->errorString(); _port->close(); return; - case QSerialPort::PermissionError: + case QGCSerialPortAdapter::PermissionError: if (_serialConfig->isAutoConnect()) { return; } @@ -369,10 +380,7 @@ void SerialWorker::_onPortErrorOccurred(QSerialPort::SerialPortError portError) const QString errorString = _port->errorString(); qCWarning(SerialLinkLog) << "Port error:" << portError << errorString; - if (!_errorEmitted) { - emit errorOccurred(errorString); - _errorEmitted = true; - } + _emitErrorOnce(errorString); } void SerialWorker::_checkPortAvailability() @@ -382,8 +390,8 @@ void SerialWorker::_checkPortAvailability() } bool portExists = false; - const auto availablePorts = QSerialPortInfo::availablePorts(); - for (const QSerialPortInfo &info : availablePorts) { + const auto availablePorts = QGCSerialPortInfo::availablePorts(); + for (const QGCSerialPortInfo &info : availablePorts) { if (info.portName() == _serialConfig->portDisplayName()) { portExists = true; break; @@ -430,7 +438,9 @@ SerialLink::~SerialLink() _workerThread->quit(); if (!_workerThread->wait(DISCONNECT_TIMEOUT_MS)) { - qCWarning(SerialLinkLog) << "Failed to wait for Serial Thread to close"; + qCWarning(SerialLinkLog) << "Worker thread did not stop within timeout, terminating"; + _workerThread->terminate(); + (void) _workerThread->wait(1000); } qCDebug(SerialLinkLog) << this; diff --git a/src/Comms/SerialLink.h b/src/Comms/SerialLink.h index d6734d608288..0e09ed0d23aa 100644 --- a/src/Comms/SerialLink.h +++ b/src/Comms/SerialLink.h @@ -2,13 +2,9 @@ #include "LinkConfiguration.h" #include "LinkInterface.h" +#include "QGCSerialPortAdapter.h" #include -#ifdef Q_OS_ANDROID -#include "qserialport.h" -#else -#include -#endif #include @@ -20,15 +16,15 @@ class QTimer; class SerialConfiguration : public LinkConfiguration { Q_OBJECT - Q_PROPERTY(qint32 baud READ baud WRITE setBaud NOTIFY baudChanged) - Q_PROPERTY(QSerialPort::DataBits dataBits READ dataBits WRITE setDataBits NOTIFY dataBitsChanged) - Q_PROPERTY(QSerialPort::FlowControl flowControl READ flowControl WRITE setFlowControl NOTIFY flowControlChanged) - Q_PROPERTY(QSerialPort::StopBits stopBits READ stopBits WRITE setStopBits NOTIFY stopBitsChanged) - Q_PROPERTY(QSerialPort::Parity parity READ parity WRITE setParity NOTIFY parityChanged) - Q_PROPERTY(QString portName READ portName WRITE setPortName NOTIFY portNameChanged) - Q_PROPERTY(QString portDisplayName READ portDisplayName NOTIFY portDisplayNameChanged) - Q_PROPERTY(bool usbDirect READ usbDirect WRITE setUsbDirect NOTIFY usbDirectChanged) - Q_PROPERTY(bool dtrForceLow READ dtrForceLow WRITE setdtrForceLow NOTIFY dtrForceLowChanged) + Q_PROPERTY(qint32 baud READ baud WRITE setBaud NOTIFY baudChanged) + Q_PROPERTY(int dataBits READ dataBits WRITE setDataBits NOTIFY dataBitsChanged) + Q_PROPERTY(int flowControl READ flowControl WRITE setFlowControl NOTIFY flowControlChanged) + Q_PROPERTY(int stopBits READ stopBits WRITE setStopBits NOTIFY stopBitsChanged) + Q_PROPERTY(int parity READ parity WRITE setParity NOTIFY parityChanged) + Q_PROPERTY(QString portName READ portName WRITE setPortName NOTIFY portNameChanged) + Q_PROPERTY(QString portDisplayName READ portDisplayName NOTIFY portDisplayNameChanged) + Q_PROPERTY(bool usbDirect READ usbDirect WRITE setUsbDirect NOTIFY usbDirectChanged) + Q_PROPERTY(bool dtrForceLow READ dtrForceLow WRITE setdtrForceLow NOTIFY dtrForceLowChanged) public: explicit SerialConfiguration(const QString &name, QObject *parent = nullptr); @@ -45,17 +41,20 @@ class SerialConfiguration : public LinkConfiguration qint32 baud() const { return _baud; } void setBaud(qint32 baud) { if (baud != _baud) { _baud = baud; emit baudChanged(); } } - QSerialPort::DataBits dataBits() const { return _dataBits; } - void setDataBits(QSerialPort::DataBits databits) { if (databits != _dataBits) { _dataBits = databits; emit dataBitsChanged(); } } + // The four enum-style properties below store integer values matching the + // QSerialPort::DataBits / FlowControl / StopBits / Parity enums (the canonical + // wire-format integers). Translation happens inside QGCSerialPortAdapter. + int dataBits() const { return _dataBits; } + void setDataBits(int databits) { if (databits != _dataBits) { _dataBits = databits; emit dataBitsChanged(); } } - QSerialPort::FlowControl flowControl() const { return _flowControl; } - void setFlowControl(QSerialPort::FlowControl flowControl) { if (flowControl != _flowControl) { _flowControl = flowControl; emit flowControlChanged(); } } + int flowControl() const { return _flowControl; } + void setFlowControl(int flowControl) { if (flowControl != _flowControl) { _flowControl = flowControl; emit flowControlChanged(); } } - QSerialPort::StopBits stopBits() const { return _stopBits; } - void setStopBits(QSerialPort::StopBits stopBits) { if (stopBits != _stopBits) { _stopBits = stopBits; emit stopBitsChanged(); } } + int stopBits() const { return _stopBits; } + void setStopBits(int stopBits) { if (stopBits != _stopBits) { _stopBits = stopBits; emit stopBitsChanged(); } } - QSerialPort::Parity parity() const { return _parity; } - void setParity(QSerialPort::Parity parity) { if (parity != _parity) { _parity = parity; emit parityChanged(); } } + int parity() const { return _parity; } + void setParity(int parity) { if (parity != _parity) { _parity = parity; emit parityChanged(); } } QString portName() const { return _portName; } void setPortName(const QString &name); @@ -84,15 +83,15 @@ class SerialConfiguration : public LinkConfiguration void dtrForceLowChanged(); private: - qint32 _baud = QSerialPort::Baud57600; - QSerialPort::DataBits _dataBits = QSerialPort::Data8; - QSerialPort::FlowControl _flowControl = QSerialPort::NoFlowControl; - QSerialPort::StopBits _stopBits = QSerialPort::OneStop; - QSerialPort::Parity _parity = QSerialPort::NoParity; + qint32 _baud = 57600; + int _dataBits = 8; // QSerialPort::Data8 + int _flowControl = 0; // QSerialPort::NoFlowControl + int _stopBits = 1; // QSerialPort::OneStop + int _parity = 0; // QSerialPort::NoParity QString _portName; QString _portDisplayName; - bool _usbDirect = false; - bool _dtrForceLow = false; + bool _usbDirect = false; + bool _dtrForceLow = false; }; /*===========================================================================*/ @@ -106,7 +105,6 @@ class SerialWorker : public QObject ~SerialWorker(); bool isConnected() const; - const QSerialPort *port() const { return _port; } signals: void connected(); @@ -125,13 +123,17 @@ private slots: void _onPortConnected(); void _onPortDisconnected(); void _onPortReadyRead(); - void _onPortBytesWritten(qint64 bytes) const; - void _onPortErrorOccurred(QSerialPort::SerialPortError portError); + void _onPortErrorOccurred(QGCSerialPortAdapter::Error portError); void _checkPortAvailability(); + /** Emit {@link #errorOccurred} at most once per connect/disconnect cycle — + * prevents writeData() failure floods (e.g. write-buffer cap firing under + * burst load) from queueing thousands of UI popups. */ + void _emitErrorOnce(const QString &errorString); + private: const SerialConfiguration *_serialConfig = nullptr; - QSerialPort *_port = nullptr; + QGCSerialPortAdapter *_port = nullptr; QTimer *_timer = nullptr; bool _errorEmitted = false; }; @@ -149,8 +151,6 @@ class SerialLink : public LinkInterface bool isConnected() const override; bool isSecureConnection() const override { return _serialConfig->usbDirect(); } - const QSerialPort *port() const { return _worker->port(); } - public slots: void disconnect() override; diff --git a/src/GPS/GPSProvider.cc b/src/GPS/GPSProvider.cc index 7bb04f682340..ab614f2ac4d7 100644 --- a/src/GPS/GPSProvider.cc +++ b/src/GPS/GPSProvider.cc @@ -9,11 +9,7 @@ #include #include -#ifdef Q_OS_ANDROID -#include "qserialport.h" -#else -#include -#endif +#include "QGCSerialPortAdapter.h" QGC_LOGGING_CATEGORY(GPSProviderLog, "GPS.GPSProvider") QGC_LOGGING_CATEGORY(GPSDriversLog, "GPS.Drivers") @@ -150,7 +146,7 @@ void GPSProvider::run() } } - if ((_serial->error() != QSerialPort::NoError) && (_serial->error() != QSerialPort::TimeoutError)) { + if ((_serial->error() != QGCSerialPortAdapter::NoError) && (_serial->error() != QGCSerialPortAdapter::TimeoutError)) { break; } } @@ -167,13 +163,13 @@ void GPSProvider::run() bool GPSProvider::_connectSerial() { - _serial = new QSerialPort(); + _serial = new QGCSerialPortAdapter(); _serial->setPortName(_device); if (!_serial->open(QIODevice::ReadWrite)) { // Give the device some time to come up. In some cases the device is not // immediately accessible right after startup for some reason. This can take 10-20s. uint32_t retries = 60; - while ((retries-- > 0) && (_serial->error() == QSerialPort::PermissionError)) { + while ((retries-- > 0) && (_serial->error() == QGCSerialPortAdapter::PermissionError)) { qCDebug(GPSProviderLog) << "Cannot open device... retrying"; msleep(500); if (_serial->open(QIODevice::ReadWrite)) { @@ -182,17 +178,17 @@ bool GPSProvider::_connectSerial() } } - if (_serial->error() != QSerialPort::NoError) { + if (_serial->error() != QGCSerialPortAdapter::NoError) { qCWarning(GPSProviderLog) << "GPS: Failed to open Serial Device" << _device << _serial->errorString(); return false; } } - (void) _serial->setBaudRate(QSerialPort::Baud9600); - (void) _serial->setDataBits(QSerialPort::Data8); - (void) _serial->setParity(QSerialPort::NoParity); - (void) _serial->setStopBits(QSerialPort::OneStop); - (void) _serial->setFlowControl(QSerialPort::NoFlowControl); + (void) _serial->setSerialParameters(QGCSerialPortAdapter::Baud9600, + QGCSerialPortAdapter::Data8, + QGCSerialPortAdapter::OneStop, + QGCSerialPortAdapter::NoParity); + (void) _serial->setFlowControl(QGCSerialPortAdapter::NoFlowControl); return true; } diff --git a/src/GPS/GPSProvider.h b/src/GPS/GPSProvider.h index 08b3608497ce..221f6fba13d1 100644 --- a/src/GPS/GPSProvider.h +++ b/src/GPS/GPSProvider.h @@ -13,7 +13,7 @@ #include "sensor_gnss_relative.h" #include "sensor_gps.h" -class QSerialPort; +class QGCSerialPortAdapter; class GPSBaseStationSupport; class GPSProvider : public QThread @@ -74,7 +74,7 @@ class GPSProvider : public QThread struct sensor_gnss_relative_s _sensorGnssRelative{}; struct sensor_gps_s _sensorGps{}; - QSerialPort *_serial = nullptr; + QGCSerialPortAdapter *_serial = nullptr; enum GPSReceiveType { Position = 1, diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3e0cf405f260..5b1ed1a4bcab 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1064,8 +1064,9 @@ void Vehicle::_handleExtendedSysState(mavlink_message_t& message) bool Vehicle::_apmArmingNotRequired() { QString armingRequireParam("ARMING_REQUIRE"); + // getParameter() returns &_defaultFact (non-null, rawValue==0) when missing — must gate on parameterExists(). return _parameterManager->parameterExists(ParameterManager::defaultComponentId, armingRequireParam) && - _parameterManager->getParameter(ParameterManager::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0; + _parameterManager->getParameter(ParameterManager::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0; } void Vehicle::_handleSysStatus(mavlink_message_t& message) @@ -1309,6 +1310,43 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message) emit flightModeChanged(flightMode()); } } + + // _benchTriggerWriteBurstStress(); // disabled — generates 145 KB/s, swamps low-baud serial telemetry links (e.g. FT232R+TELEM at 57600). +} + +// ============================================================================ +// BENCHMARK INSTRUMENTATION (debug-only). Fires a 10 Hz × 850-msg heartbeat +// burst on the primary link to saturate write-path drain. Started after the +// 5th heartbeat; runs until Vehicle is destroyed (timer parented to `this`). +// To strip: remove this method, its declaration in Vehicle.h, and the +// _benchTriggerWriteBurstStress() call at the end of _handleHeartbeat(). +// ============================================================================ +void Vehicle::_benchTriggerWriteBurstStress() +{ + static int s_hbSeen = 0; + static QPointer s_burstTimer; // QPointer auto-nulls when the parent Vehicle is destroyed (link bounce → fresh re-arm). + if (s_burstTimer) return; + if (++s_hbSeen < 5) return; + s_hbSeen = 0; + + s_burstTimer = new QTimer(this); + s_burstTimer->setInterval(100); + QObject::connect(s_burstTimer, &QTimer::timeout, this, [this]() { + SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock(); + if (!sharedLink) return; + constexpr int kBurst = 850; + mavlink_message_t burstMsg; + for (int i = 0; i < kBurst; ++i) { + mavlink_msg_heartbeat_pack_chan( + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::getComponentId()), + sharedLink->mavlinkChannel(), + &burstMsg, + MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, 0, 0, MAV_STATE_ACTIVE); + sendMessageOnLinkThreadSafe(sharedLink.get(), burstMsg); + } + }); + s_burstTimer->start(); } void Vehicle::_handleCurrentMode(mavlink_message_t& message) @@ -1411,7 +1449,8 @@ int Vehicle::motorCount() { uint8_t frameType = 0; if (_vehicleType == MAV_TYPE_SUBMARINE) { - frameType = parameterManager()->getParameter(_compID, "FRAME_CONFIG")->rawValue().toInt(); + Fact *param = parameterManager()->getParameter(_compID, "FRAME_CONFIG"); + if (param) frameType = param->rawValue().toInt(); } return QGCMAVLink::motorCount(_vehicleType, frameType); } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 51076c5479d0..051edab52aa9 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -851,6 +851,7 @@ private slots: void _handlePing (LinkInterface* link, mavlink_message_t& message); void _handleHomePosition (mavlink_message_t& message); void _handleHeartbeat (mavlink_message_t& message); + void _benchTriggerWriteBurstStress (); // DEBUG: write-path stress benchmark; remove with body in Vehicle.cc. void _handleCurrentMode (mavlink_message_t& message); void _handleRCChannels (mavlink_message_t& message); void _handleBatteryStatus (mavlink_message_t& message); diff --git a/src/Vehicle/VehicleSetup/Bootloader.cc b/src/Vehicle/VehicleSetup/Bootloader.cc index 742ab25035b7..2f014666f20b 100644 --- a/src/Vehicle/VehicleSetup/Bootloader.cc +++ b/src/Vehicle/VehicleSetup/Bootloader.cc @@ -10,6 +10,24 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "VehicleSetup.FirmwareUpgrade") QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "VehicleSetup.FirmwareUpgrade:verbose") +namespace { +QString _hexPreview(const uint8_t* data, qint64 len) +{ + constexpr qint64 kCap = 32; + const qint64 n = qMin(len, kCap); + QString out; + out.reserve(int(n * 3)); + for (qint64 i = 0; i < n; ++i) { + if (i) out += QLatin1Char(' '); + out += QString::asprintf("%02x", data[i]); + } + if (len > kCap) { + out += QStringLiteral(" …(+%1)").arg(len - kCap); + } + return out; +} +} // namespace + /// This class manages interactions with the bootloader Bootloader::Bootloader(bool sikRadio, QObject *parent) : QObject (parent) @@ -23,11 +41,11 @@ bool Bootloader::open(const QString portName) qCDebug(FirmwareUpgradeLog) << "open:" << portName; _port.setPortName (portName); - _port.setBaudRate (QSerialPort::Baud115200); - _port.setDataBits (QSerialPort::Data8); - _port.setParity (QSerialPort::NoParity); - _port.setStopBits (QSerialPort::OneStop); - _port.setFlowControl(QSerialPort::NoFlowControl); + _port.setSerialParameters(QGCSerialPortAdapter::Baud115200, + QGCSerialPortAdapter::Data8, + QGCSerialPortAdapter::OneStop, + QGCSerialPortAdapter::NoParity); + _port.setFlowControl(QGCSerialPortAdapter::NoFlowControl); if (!_port.open(QIODevice::ReadWrite)) { _errorString = tr("Open failed on port %1: %2").arg(portName, _port.errorString()); @@ -78,7 +96,7 @@ bool Bootloader::getBoardInfo(uint32_t& bootloaderVersion, uint32_t& boardID, ui } else { qCDebug(FirmwareUpgradeLog) << "Radio in normal mode"; _port.readAll(); - _port.setBaudRate(QSerialPort::Baud57600); + _port.setBaudRate(QGCSerialPortAdapter::Baud57600); // Put radio into command mode _write("+++"); if (!_port.waitForReadyRead(2000)) { @@ -158,7 +176,7 @@ bool Bootloader::initFlashSequence(void) _errorString = tr("Unable to reboot radio (ready read)"); return false; } - _port.setBaudRate(QSerialPort::Baud115200); + _port.setBaudRate(QGCSerialPortAdapter::Baud115200); if (!_sync()) { return false; @@ -232,6 +250,8 @@ bool Bootloader::_write(const uint8_t* data, qint64 maxSize) return false; } + qCDebug(FirmwareUpgradeVerboseLog).noquote() + << QStringLiteral("TX n=%1 hex=%2").arg(maxSize).arg(_hexPreview(data, maxSize)); return true; } @@ -248,7 +268,12 @@ bool Bootloader::_read(uint8_t* data, qint64 cBytesExpected, int readTimeout) timeout.start(); while (_port.bytesAvailable() < cBytesExpected) { if (timeout.elapsed() > readTimeout) { - _errorString = tr("Timeout waiting for bytes to be available"); + const qint64 avail = _port.bytesAvailable(); + _errorString = tr("Timeout waiting for bytes (expected=%1 available=%2 elapsed=%3ms)") + .arg(cBytesExpected).arg(avail).arg(timeout.elapsed()); + qCDebug(FirmwareUpgradeVerboseLog).noquote() + << QStringLiteral("RX timeout expected=%1 available=%2 elapsed=%3ms") + .arg(cBytesExpected).arg(avail).arg(timeout.elapsed()); return false; } _port.waitForReadyRead(100); @@ -262,6 +287,9 @@ bool Bootloader::_read(uint8_t* data, qint64 cBytesExpected, int readTimeout) return false; } + qCDebug(FirmwareUpgradeVerboseLog).noquote() + << QStringLiteral("RX n=%1 elapsed=%2ms hex=%3") + .arg(bytesRead).arg(timeout.elapsed()).arg(_hexPreview(data, bytesRead)); return true; } @@ -715,11 +743,14 @@ bool Bootloader::_sync(void) _port.readAll(); bool success = false; for (int i=0; i<3; i++) { + qCDebug(FirmwareUpgradeVerboseLog) << "sync attempt" << (i + 1) << "of 3"; success = _syncWorker(); if (success) { + qCDebug(FirmwareUpgradeVerboseLog) << "sync attempt" << (i + 1) << "succeeded"; return true; } + qCDebug(FirmwareUpgradeVerboseLog) << "sync attempt" << (i + 1) << "failed:" << _errorString; } return success; } diff --git a/src/Vehicle/VehicleSetup/Bootloader.h b/src/Vehicle/VehicleSetup/Bootloader.h index ae6d9fe2a2de..a5e9e66f5bba 100644 --- a/src/Vehicle/VehicleSetup/Bootloader.h +++ b/src/Vehicle/VehicleSetup/Bootloader.h @@ -2,11 +2,7 @@ #include -#ifdef Q_OS_ANDROID -#include "qserialport.h" -#else -#include -#endif +#include "QGCSerialPortAdapter.h" class FirmwareImage; @@ -96,7 +92,7 @@ class Bootloader : public QObject READ_MULTI_MAX = 0x28 ///< read size for PROTO_READ_MULTI, must be multiple of 4. Sik Radio max size is 0x28 }; - QSerialPort _port; + QGCSerialPortAdapter _port; bool _sikRadio = false; bool _inBootloaderMode = false; ///< true: board is in bootloader mode, false: special case for SiK Radio, board is in command mode uint32_t _boardID = 0; ///< board id for currently connected board diff --git a/src/Vehicle/VehicleSetup/FirmwareUpgrade.qml b/src/Vehicle/VehicleSetup/FirmwareUpgrade.qml index 21b115c3c438..942645f49e2a 100644 --- a/src/Vehicle/VehicleSetup/FirmwareUpgrade.qml +++ b/src/Vehicle/VehicleSetup/FirmwareUpgrade.qml @@ -35,6 +35,12 @@ SetupPage { readonly property string unplugReplugText: highlightPrefix + qsTr("Now unplug your device and plug it back in to enter bootloader mode.") + highlightSuffix readonly property string flashFailText: qsTr("If upgrade failed, make sure to connect ") + highlightPrefix + qsTr("directly") + highlightSuffix + qsTr(" to a powered USB port on your computer, not through a USB hub. ") + qsTr("Also make sure you are only powered via USB ") + highlightPrefix + qsTr("not battery") + highlightSuffix + "." + readonly property string androidNoteText: highlightPrefix + qsTr("Android USB note: ") + highlightSuffix + + qsTr("the bootloader watchdog (~5 s) is shorter than the Android permission dialog. ") + + qsTr("Before flashing, force-stop QGroundControl and replug the device — Android will offer ") + + highlightPrefix + qsTr("\"Use by default for this USB device\"") + highlightSuffix + + qsTr(" with an ") + highlightPrefix + qsTr("Always") + highlightSuffix + + qsTr(" checkbox. Tick it for both the bootloader and the application device, then upgrade.") readonly property int _defaultFimwareTypePX4: 12 readonly property int _defaultFimwareTypeAPM: 3 @@ -118,6 +124,9 @@ SetupPage { onActiveVehicleChanged: { if (!globals.activeVehicle && !_flashStarted) { statusTextArea.append(plugInText) + if (Qt.platform.os === "android") { + statusTextArea.append(androidNoteText) + } } } diff --git a/src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc index 6b123bcf5ddc..07fd938830a9 100644 --- a/src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.cc @@ -252,7 +252,7 @@ QStringList FirmwareUpgradeController::availableBoardsName(void) return names; } -void FirmwareUpgradeController::_foundBoard(bool firstAttempt, const QSerialPortInfo& info, int boardType, QString boardName) +void FirmwareUpgradeController::_foundBoard(bool firstAttempt, const QGCSerialPortInfo& info, int boardType, QString boardName) { _boardInfo = info; _boardType = static_cast(boardType); diff --git a/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h index c785503ff1ea..2008a61c09a3 100644 --- a/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h +++ b/src/Vehicle/VehicleSetup/FirmwareUpgradeController.h @@ -167,7 +167,7 @@ class FirmwareUpgradeController : public QObject private slots: void _firmwareDownloadProgress (qint64 curr, qint64 total); void _firmwareDownloadComplete (bool success, const QString &localFile, const QString &errorMsg); - void _foundBoard (bool firstAttempt, const QSerialPortInfo& portInfo, int boardType, QString boardName); + void _foundBoard (bool firstAttempt, const QGCSerialPortInfo& portInfo, int boardType, QString boardName); void _noBoardFound (void); void _boardGone (void); void _foundBoardInfo (int bootloaderVersion, int boardID, int flashSize); @@ -238,7 +238,7 @@ private slots: bool _searchingForBoard; ///< true: searching for board, false: search for bootloader - QSerialPortInfo _boardInfo; + QGCSerialPortInfo _boardInfo; QGCSerialPortInfo::BoardType_t _boardType; QString _boardTypeName; diff --git a/src/Vehicle/VehicleSetup/VehicleConfigView.qml b/src/Vehicle/VehicleSetup/VehicleConfigView.qml index a5f0851ca3c2..1ee7914b0f46 100644 --- a/src/Vehicle/VehicleSetup/VehicleConfigView.qml +++ b/src/Vehicle/VehicleSetup/VehicleConfigView.qml @@ -516,7 +516,7 @@ Rectangle { ConfigButton { id: firmwareButton icon.source: "/qmlimages/FirmwareUpgradeIcon.png" - visible: !ScreenTools.isMobile && _corePlugin.options.showFirmwareUpgrade && + visible: Qt.platform.os !== "ios" && _corePlugin.options.showFirmwareUpgrade && vehicleConfigView._searchQuery.trim() === "" text: qsTr("Firmware") Layout.fillWidth: true diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 7f4ef97f8e7e..0b40f0fbec1b 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -114,6 +114,9 @@ add_qgc_test(BluetoothEmulatedAdapterTest LABELS Integration Comms) add_qgc_test(BluetoothLiveAdapterTest LABELS Integration Comms) add_qgc_test(BluetoothWorkerTest LABELS Unit Comms) add_qgc_test(LinkConfigurationTest LABELS Unit Comms RESOURCE_LOCK Settings TempFiles) +add_qgc_test(MockQSerialPortEngineTest LABELS Unit Comms) +add_qgc_test(QGCAndroidSerialPortTest LABELS Unit Comms) +add_qgc_test(QGCSerialPortAdapterTest LABELS Unit Comms) add_qgc_test(QGCSerialPortInfoTest LABELS Unit Comms) # ---------------------------------------------------------------------------- diff --git a/test/Comms/Android/CMakeLists.txt b/test/Comms/Android/CMakeLists.txt new file mode 100644 index 000000000000..f6e0502e53d5 --- /dev/null +++ b/test/Comms/Android/CMakeLists.txt @@ -0,0 +1,27 @@ +# ============================================================================ +# Android Serial Engine Mock + Tests +# Host-buildable tests for the IQSerialPortEngine contract via MockQSerialPortEngine. +# The production QAndroidSerialEngine and QSerialPortPrivate are Android-only and not +# exercised here — they share the interface so the contract is validated for both. +# ============================================================================ + +target_sources(${CMAKE_PROJECT_NAME} + PRIVATE + MockQSerialPortEngine.cc + MockQSerialPortEngine.h + MockQSerialPortEngineTest.cc + MockQSerialPortEngineTest.h + QGCAndroidSerialPortTest.cc + QGCAndroidSerialPortTest.h +) + +# Pulls in iqserialportengine_p.h, qandroidserialenginereceiver_p.h, AndroidSerial.h. +# These headers are JNI-free and host-buildable; the matching .cpp files stay Android-only. +target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} + ${CMAKE_SOURCE_DIR}/src/Android + ${CMAKE_SOURCE_DIR}/src/Android/qtandroidserialport +) + +# QGCAndroidSerialPort is linked from src/Android/qtandroidserialport/CMakeLists.txt +# on both host and Android — adapter.cc references its symbols. diff --git a/test/Comms/Android/MockQSerialPortEngine.cc b/test/Comms/Android/MockQSerialPortEngine.cc new file mode 100644 index 000000000000..153d5be95f6e --- /dev/null +++ b/test/Comms/Android/MockQSerialPortEngine.cc @@ -0,0 +1,143 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#include "MockQSerialPortEngine.h" + +#include + +MockQSerialPortEngine::MockQSerialPortEngine(QAndroidSerialEngineReceiver* sink, QObject* owner) + : _sink(sink), _owner(owner) +{ +} + +MockQSerialPortEngine::~MockQSerialPortEngine() = default; + +bool MockQSerialPortEngine::open(const QString& portName, + const AndroidSerial::SerialParameters& params, + int flowControl, bool assertDtr) +{ + if (_openShouldFail) return false; + + _portName = portName; + _openParams = params; + _flowControl = flowControl; + _dtrAsserted = assertDtr; + _state = State::Open; + return true; +} + +void MockQSerialPortEngine::close() +{ + _state = State::Closed; + _readThreadRunning = false; +} + +bool MockQSerialPortEngine::setParameters(const AndroidSerial::SerialParameters& p) +{ + if (_state != State::Open) return false; + _openParams = p; + ++_setParametersCallCount; + return true; +} + +bool MockQSerialPortEngine::setDataTerminalReady(bool set) +{ + if (_state != State::Open) return false; + _dtrAsserted = set; + return true; +} + +bool MockQSerialPortEngine::setRequestToSend(bool set) +{ + if (_state != State::Open) return false; + _rtsAsserted = set; + return true; +} + +bool MockQSerialPortEngine::setFlowControl(int flowControl) +{ + if (_state != State::Open) return false; + _flowControl = flowControl; + return true; +} + +bool MockQSerialPortEngine::setBreak(bool set) +{ + if (_state != State::Open) return false; + _breakSet = set; + return true; +} + +bool MockQSerialPortEngine::purgeBuffers(bool input, bool /*output*/) +{ + if (_state != State::Open) return false; + if (input) _staged.clear(); + return true; +} + +int MockQSerialPortEngine::writeSync(QSpan data, int /*timeout*/) +{ + if (_state != State::Open) return -1; + _syncWrites.append(QByteArray(data.data(), static_cast(data.size()))); + if (_nextWriteReturn != -2) { + const int rv = _nextWriteReturn; + _nextWriteReturn = -2; + return rv; + } + return static_cast(data.size()); +} + +int MockQSerialPortEngine::writeAsync(QSpan data, int /*timeout*/) +{ + if (_state != State::Open) return -1; + _asyncWrites.append(QByteArray(data.data(), static_cast(data.size()))); + if (_nextWriteReturn != -2) { + const int rv = _nextWriteReturn; + _nextWriteReturn = -2; + return rv; + } + return static_cast(data.size()); +} + +bool MockQSerialPortEngine::startReadThread() +{ + if (_state != State::Open) return false; + _readThreadRunning = true; + return true; +} + +bool MockQSerialPortEngine::stopReadThread() +{ + _readThreadRunning = false; + return true; +} + +QByteArray MockQSerialPortEngine::waitForReadyRead(int /*msecs*/, qint64 /*ownerBufferSize*/) +{ + QByteArray out; + std::swap(out, _staged); + return out; +} + +// --- Test driver helpers --- + +void MockQSerialPortEngine::simulateRead(const QByteArray& data) +{ + // Production engine marshals via QueuedConnection; the mock is synchronous so tests + // can assert without an event loop. If a test needs queued semantics, replace this + // body with QMetaObject::invokeMethod(... Qt::QueuedConnection). + if (!_sink) return; + QByteArray copy = data; + _sink->dataReady(std::move(copy)); +} + +void MockQSerialPortEngine::simulateClose() +{ + if (!_sink) return; + _sink->closeNotification(); +} + +void MockQSerialPortEngine::simulateException(AndroidSerial::JavaExceptionKind kind, const QString& msg) +{ + if (!_sink) return; + _sink->exceptionNotification(kind, msg); +} diff --git a/test/Comms/Android/MockQSerialPortEngine.h b/test/Comms/Android/MockQSerialPortEngine.h new file mode 100644 index 000000000000..2ecede4fdb83 --- /dev/null +++ b/test/Comms/Android/MockQSerialPortEngine.h @@ -0,0 +1,96 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "iqserialportengine_p.h" +#include "qandroidserialenginereceiver_p.h" + +#include +#include +#include + +QT_BEGIN_NAMESPACE +class QObject; +QT_END_NAMESPACE + +// In-memory implementation of IQSerialPortEngine for host-side testing. Drives the +// receiver synchronously via simulate*() helpers; tests don't need to spin an event loop. +class MockQSerialPortEngine : public IQSerialPortEngine +{ +public: + MockQSerialPortEngine(QAndroidSerialEngineReceiver* sink, QObject* owner); + ~MockQSerialPortEngine() override; + + // --- IQSerialPortEngine --- + [[nodiscard]] bool open(const QString& portName, + const AndroidSerial::SerialParameters& params, + int flowControl, bool assertDtr) override; + void close() override; + bool isOpen() const override { return _state == State::Open; } + State state() const override { return _state; } + int deviceHandle() const override { return _deviceHandle; } + + [[nodiscard]] bool setParameters(const AndroidSerial::SerialParameters& p) override; + [[nodiscard]] bool setDataTerminalReady(bool set) override; + [[nodiscard]] bool setRequestToSend(bool set) override; + [[nodiscard]] bool setFlowControl(int flowControl) override; + int flowControl() const override { return _flowControl; } + [[nodiscard]] bool setBreak(bool set) override; + [[nodiscard]] bool purgeBuffers(bool input, bool output) override; + + quint32 controlLinesMask() const override { return _controlLinesMask; } + + int writeSync(QSpan data, int timeout) override; + int writeAsync(QSpan data, int timeout) override; + + [[nodiscard]] bool startReadThread() override; + [[nodiscard]] bool stopReadThread() override; + bool readThreadRunning() const override { return _readThreadRunning; } + + void setReadBufferMaxSize(qint64 bytes) override { _readBufferMaxSize = bytes; } + void clearReadStaging() override { _staged.clear(); } + QByteArray waitForReadyRead(int msecs, qint64 ownerBufferSize) override; + + // --- Test driver helpers (synchronous receiver invocation) --- + void simulateRead(const QByteArray& data); + void simulateClose(); + void simulateException(AndroidSerial::JavaExceptionKind kind, const QString& msg); + + // --- Inspection / fault injection --- + const QList& syncWrites() const { return _syncWrites; } + const QList& asyncWrites() const { return _asyncWrites; } + QString lastPortName() const { return _portName; } + AndroidSerial::SerialParameters lastOpenParams() const { return _openParams; } + int setParametersCallCount() const { return _setParametersCallCount; } + bool dtrAsserted() const { return _dtrAsserted; } + bool rtsAsserted() const { return _rtsAsserted; } + bool breakSet() const { return _breakSet; } + + void setOpenShouldFail(bool b) { _openShouldFail = b; } + void setNextWriteFailure(int returnValue) { _nextWriteReturn = returnValue; } + void setControlLinesMask(quint32 mask) { _controlLinesMask = mask; } + +private: + QAndroidSerialEngineReceiver* _sink; + [[maybe_unused]] QObject* _owner; // Held for parity with production engine ctor; mock is single-threaded. + State _state = State::Closed; + + int _deviceHandle = 1001; + int _flowControl = 0; + bool _dtrAsserted = false; + bool _rtsAsserted = false; + bool _breakSet = false; + bool _readThreadRunning = false; + bool _openShouldFail = false; + int _nextWriteReturn = -2; // -2 sentinel = use length; otherwise return this value once + quint32 _controlLinesMask = 0; + qint64 _readBufferMaxSize = 0; + + QString _portName; + AndroidSerial::SerialParameters _openParams{}; + int _setParametersCallCount = 0; + + QByteArray _staged; + QList _syncWrites; + QList _asyncWrites; +}; diff --git a/test/Comms/Android/MockQSerialPortEngineTest.cc b/test/Comms/Android/MockQSerialPortEngineTest.cc new file mode 100644 index 000000000000..88ea70400cea --- /dev/null +++ b/test/Comms/Android/MockQSerialPortEngineTest.cc @@ -0,0 +1,250 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#include "MockQSerialPortEngineTest.h" + +#include "MockQSerialPortEngine.h" +#include "UnitTest.h" +#include "qandroidserialenginereceiver_p.h" + +#include +#include + +UT_REGISTER_TEST(MockQSerialPortEngineTest, TestLabel::Unit, TestLabel::Comms) + +namespace { + +// Minimal QAndroidSerialEngineReceiver that records all callbacks for assertion. +class RecordingReceiver : public QAndroidSerialEngineReceiver +{ +public: + void dataReady(QByteArray&& bytes) override + { + dataReadyCalls.append(std::move(bytes)); + } + void closeNotification() override + { + ++closeCount; + } + void exceptionNotification(AndroidSerial::JavaExceptionKind kind, const QString& message) override + { + exceptions.append({kind, message}); + } + + struct Exc { AndroidSerial::JavaExceptionKind kind; QString message; }; + QList dataReadyCalls; + int closeCount = 0; + QList exceptions; +}; + +AndroidSerial::SerialParameters defaultParams() +{ + return AndroidSerial::SerialParameters{ + .baudRate = 57600, + .dataBits = 8, + .stopBits = 1, + .parity = AndroidSerial::NoParity, + }; +} + +} // namespace + +void MockQSerialPortEngineTest::_openClose_transitionsState() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + QCOMPARE(eng.state(), IQSerialPortEngine::State::Closed); + QVERIFY(!eng.isOpen()); + + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), AndroidSerial::NoFlowControl, /*assertDtr=*/true)); + QCOMPARE(eng.state(), IQSerialPortEngine::State::Open); + QVERIFY(eng.isOpen()); + QCOMPARE(eng.lastPortName(), QStringLiteral("/dev/mock0")); + QCOMPARE(eng.dtrAsserted(), true); + + eng.close(); + QCOMPARE(eng.state(), IQSerialPortEngine::State::Closed); + QVERIFY(!eng.isOpen()); +} + +void MockQSerialPortEngineTest::_openShouldFail_returnsFalseLeavesClosed() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + eng.setOpenShouldFail(true); + + QVERIFY(!eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + QCOMPARE(eng.state(), IQSerialPortEngine::State::Closed); +} + +void MockQSerialPortEngineTest::_setters_failBeforeOpen() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + QVERIFY(!eng.setDataTerminalReady(true)); + QVERIFY(!eng.setRequestToSend(true)); + QVERIFY(!eng.setBreak(true)); + QVERIFY(!eng.setFlowControl(AndroidSerial::RtsCtsFlowControl)); + QVERIFY(!eng.setParameters(defaultParams())); + QVERIFY(!eng.purgeBuffers(true, true)); +} + +void MockQSerialPortEngineTest::_setters_succeedAfterOpen() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, false)); + + QVERIFY(eng.setDataTerminalReady(true)); + QCOMPARE(eng.dtrAsserted(), true); + + QVERIFY(eng.setRequestToSend(true)); + QCOMPARE(eng.rtsAsserted(), true); + + QVERIFY(eng.setBreak(true)); + QCOMPARE(eng.breakSet(), true); + + QVERIFY(eng.setFlowControl(AndroidSerial::RtsCtsFlowControl)); + QCOMPARE(eng.flowControl(), AndroidSerial::RtsCtsFlowControl); +} + +void MockQSerialPortEngineTest::_writeSync_recordsBytes_returnsLength() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + + const QByteArray payload("hello", 5); + const int written = eng.writeSync(QSpan(payload.constData(), payload.size()), 1000); + QCOMPARE(written, 5); + QCOMPARE(eng.syncWrites().size(), 1); + QCOMPARE(eng.syncWrites().first(), payload); +} + +void MockQSerialPortEngineTest::_writeAsync_recordsBytes_returnsLength() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + + const QByteArray payload("xyz", 3); + const int written = eng.writeAsync(QSpan(payload.constData(), payload.size()), 1000); + QCOMPARE(written, 3); + QCOMPARE(eng.asyncWrites().size(), 1); + QCOMPARE(eng.asyncWrites().first(), payload); +} + +void MockQSerialPortEngineTest::_writeFailure_returnsInjectedValue() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + + eng.setNextWriteFailure(-1); + const QByteArray payload("fail", 4); + QCOMPARE(eng.writeSync(QSpan(payload.constData(), payload.size()), 1000), -1); + // Second call returns to default (length). + QCOMPARE(eng.writeSync(QSpan(payload.constData(), payload.size()), 1000), 4); +} + +void MockQSerialPortEngineTest::_purgeBuffers_clearsInputStaging() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + + // No staging API directly; verify the purge succeeds and waitForReadyRead returns empty. + QVERIFY(eng.purgeBuffers(/*input=*/true, /*output=*/true)); + QCOMPARE(eng.waitForReadyRead(0, 0), QByteArray()); +} + +void MockQSerialPortEngineTest::_waitForReadyRead_drainsStaging() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + + // simulateRead delivers via the receiver, not via waitForReadyRead — that path mirrors + // the production async-read flow. waitForReadyRead is the blocking wait pulled from + // staging; the mock's _staged starts empty, so it returns empty. + QCOMPARE(eng.waitForReadyRead(0, 0), QByteArray()); +} + +void MockQSerialPortEngineTest::_simulateRead_invokesDataReady() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + const QByteArray payload("\x01\x02\x03", 3); + eng.simulateRead(payload); + + QCOMPARE(rx.dataReadyCalls.size(), 1); + QCOMPARE(rx.dataReadyCalls.first(), payload); +} + +void MockQSerialPortEngineTest::_simulateClose_invokesCloseNotification() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + eng.simulateClose(); + eng.simulateClose(); + QCOMPARE(rx.closeCount, 2); +} + +void MockQSerialPortEngineTest::_simulateException_invokesExceptionNotification() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + eng.simulateException(AndroidSerial::JavaExceptionKind::Resource, QStringLiteral("cable yanked")); + QCOMPARE(rx.exceptions.size(), 1); + QCOMPARE(rx.exceptions.first().kind, AndroidSerial::JavaExceptionKind::Resource); + QCOMPARE(rx.exceptions.first().message, QStringLiteral("cable yanked")); +} + +void MockQSerialPortEngineTest::_readThread_lifecycle() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + // Cannot start before open. + QVERIFY(!eng.startReadThread()); + QVERIFY(!eng.readThreadRunning()); + + QVERIFY(eng.open(QStringLiteral("/dev/mock0"), defaultParams(), 0, true)); + QVERIFY(eng.startReadThread()); + QVERIFY(eng.readThreadRunning()); + + QVERIFY(eng.stopReadThread()); + QVERIFY(!eng.readThreadRunning()); + + // close() also clears the running flag. + QVERIFY(eng.startReadThread()); + eng.close(); + QVERIFY(!eng.readThreadRunning()); +} + +void MockQSerialPortEngineTest::_controlLines_returnsInjectedMask() +{ + RecordingReceiver rx; + QObject owner; + MockQSerialPortEngine eng(&rx, &owner); + + eng.setControlLinesMask(0xDEAD); + QCOMPARE(eng.controlLinesMask(), 0xDEADu); +} diff --git a/test/Comms/Android/MockQSerialPortEngineTest.h b/test/Comms/Android/MockQSerialPortEngineTest.h new file mode 100644 index 000000000000..11b1a0d6a9ef --- /dev/null +++ b/test/Comms/Android/MockQSerialPortEngineTest.h @@ -0,0 +1,28 @@ +// SPDX-License-Identifier: LicenseRef-Qt-Commercial OR LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "UnitTest.h" + +// Validates the MockQSerialPortEngine implementation of IQSerialPortEngine. Establishes +// the contract that future MockQSerialPortEngine-backed integration tests rely on. +class MockQSerialPortEngineTest : public UnitTest +{ + Q_OBJECT + +private slots: + void _openClose_transitionsState(); + void _openShouldFail_returnsFalseLeavesClosed(); + void _setters_failBeforeOpen(); + void _setters_succeedAfterOpen(); + void _writeSync_recordsBytes_returnsLength(); + void _writeAsync_recordsBytes_returnsLength(); + void _writeFailure_returnsInjectedValue(); + void _purgeBuffers_clearsInputStaging(); + void _waitForReadyRead_drainsStaging(); + void _simulateRead_invokesDataReady(); + void _simulateClose_invokesCloseNotification(); + void _simulateException_invokesExceptionNotification(); + void _readThread_lifecycle(); + void _controlLines_returnsInjectedMask(); +}; diff --git a/test/Comms/Android/QGCAndroidSerialPortTest.cc b/test/Comms/Android/QGCAndroidSerialPortTest.cc new file mode 100644 index 000000000000..a4c21ac82012 --- /dev/null +++ b/test/Comms/Android/QGCAndroidSerialPortTest.cc @@ -0,0 +1,315 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#include "QGCAndroidSerialPortTest.h" + +#include "MockQSerialPortEngine.h" +#include "QGCAndroidSerialPort.h" +#include "UnitTest.h" + +#include +#include +#include +#include + +UT_REGISTER_TEST(QGCAndroidSerialPortTest, TestLabel::Unit, TestLabel::Comms) + +namespace { + +// Process-wide latched pointer to the most recently created MockQSerialPortEngine. Lets +// each test inspect the engine without threading it through the factory return type. +MockQSerialPortEngine* g_lastMock = nullptr; + +void installMockFactory() +{ + g_lastMock = nullptr; + QGCAndroidSerialPortFactory::setEngineFactory( + [](QAndroidSerialEngineReceiver* sink, QObject* owner) { + auto mock = std::make_unique(sink, owner); + g_lastMock = mock.get(); + return std::unique_ptr(std::move(mock)); + }); +} + +void installNullFactory() +{ + g_lastMock = nullptr; + QGCAndroidSerialPortFactory::setEngineFactory( + [](QAndroidSerialEngineReceiver*, QObject*) { + return std::unique_ptr{}; + }); +} + +} // namespace + +void QGCAndroidSerialPortTest::cleanup() +{ + QGCAndroidSerialPortFactory::resetEngineFactory(); + g_lastMock = nullptr; + UnitTest::cleanup(); +} + +void QGCAndroidSerialPortTest::_open_pushesConfigToEngine() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.setBaudRate(115200)); + QVERIFY(port.setDataBits(QGCDataBits::Data7)); + QVERIFY(port.setParity(QGCParity::Even)); + QVERIFY(port.setStopBits(QGCStopBits::Two)); + QVERIFY(port.setFlowControl(QGCFlowControl::HardwareRtsCts)); + + QVERIFY(port.open(QIODevice::ReadWrite)); + QVERIFY(port.isOpen()); + QVERIFY(g_lastMock); + QCOMPARE(g_lastMock->lastPortName(), QStringLiteral("/dev/mock0")); + + const auto p = g_lastMock->lastOpenParams(); + QCOMPARE(p.baudRate, 115200); + QCOMPARE(p.dataBits, 7); + QCOMPARE(p.stopBits, 2); + QCOMPARE(p.parity, static_cast(AndroidSerial::EvenParity)); + + QCOMPARE(g_lastMock->flowControl(), static_cast(AndroidSerial::RtsCtsFlowControl)); + QVERIFY(g_lastMock->dtrAsserted()); + + port.close(); +} + +void QGCAndroidSerialPortTest::_open_factoryReturningNull_fails() +{ + installNullFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(!port.open(QIODevice::ReadWrite)); + QVERIFY(!port.isOpen()); + QCOMPARE(port.error(), QGCSerialPortError::OpenFailed); +} + +void QGCAndroidSerialPortTest::_close_emitsAboutToCloseBeforeTeardown() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + // Captures isOpen() at the moment aboutToClose fires. QIODevice contract: the device + // is still readable/writable when aboutToClose runs, so slots can drain pending data. + bool wasOpenInSlot = false; + QObject::connect(&port, &QIODevice::aboutToClose, &port, + [&] { wasOpenInSlot = port.isOpen(); }); + + port.close(); + QVERIFY(wasOpenInSlot); + QVERIFY(!port.isOpen()); +} + +void QGCAndroidSerialPortTest::_close_emitsReadChannelFinished() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QSignalSpy finishedSpy(&port, &QIODevice::readChannelFinished); + port.close(); + QCOMPARE(finishedSpy.count(), 1); +} + +void QGCAndroidSerialPortTest::_close_clearsBuffersAndState() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + // Stage some incoming bytes via the receiver path so bytesAvailable goes nonzero. + g_lastMock->simulateRead(QByteArray("hello", 5)); + QVERIFY(port.bytesAvailable() > 0); + + port.close(); + QCOMPARE(port.bytesAvailable(), qint64(0)); + QCOMPARE(port.bytesToWrite(), qint64(0)); + QCOMPARE(port.error(), QGCSerialPortError::NoError); +} + +void QGCAndroidSerialPortTest::_writeData_routesThroughEngine() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + const QByteArray payload("ping", 4); + const qint64 written = port.write(payload); + QCOMPARE(written, qint64(4)); + + // Drain happens on the event loop. Pump once so the QChronoTimer fires. + QTest::qWait(20); + + QCOMPARE(g_lastMock->syncWrites().size(), 1); + QCOMPARE(g_lastMock->syncWrites().first(), payload); + + port.close(); +} + +void QGCAndroidSerialPortTest::_dataReady_fillsReadBuffer_emitsReadyRead() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QSignalSpy readySpy(&port, &QIODevice::readyRead); + + const QByteArray payload("abc\x01\x02", 5); + g_lastMock->simulateRead(payload); + + QCOMPARE(readySpy.count(), 1); + QCOMPARE(port.bytesAvailable(), qint64(5)); + QCOMPARE(port.readAll(), payload); + + port.close(); +} + +void QGCAndroidSerialPortTest::_exception_resourceUnavailable_setsErrorAndCloses() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QSignalSpy errorSpy(&port, &QGCAndroidSerialPort::errorOccurred); + + g_lastMock->simulateException(AndroidSerial::JavaExceptionKind::Resource, + QStringLiteral("cable yanked")); + + QCOMPARE(errorSpy.count(), 1); + QCOMPARE(errorSpy.first().first().value(), + QGCSerialPortError::ResourceUnavailable); + + // Resource exceptions trigger eager close so queued writes stop spamming the engine. + QVERIFY(!port.isOpen()); +} + +void QGCAndroidSerialPortTest::_exception_permission_setsErrorOnly() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QSignalSpy errorSpy(&port, &QGCAndroidSerialPort::errorOccurred); + + g_lastMock->simulateException(AndroidSerial::JavaExceptionKind::Permission, + QStringLiteral("USB permission denied")); + + QCOMPARE(errorSpy.count(), 1); + QCOMPARE(errorSpy.first().first().value(), + QGCSerialPortError::PermissionDenied); + // Permission errors do NOT auto-close. + QVERIFY(port.isOpen()); + + port.close(); +} + +void QGCAndroidSerialPortTest::_expectClosure_suppressesResourceExceptionDuringClose() +{ + // The _expectClosure flag is set at the top of close() to mask the racing Java + // IOException from the forced close. Exercising the synchronous-during-aboutToClose + // race via a mock would require re-entrancy of close() which is not the production + // path — the real exception arrives on the owner thread via a queued metacall and is + // suppressed naturally by close() finishing first. Asserting only the structural + // invariant: after a clean close, no error was set. + installMockFactory(); + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QSignalSpy errorSpy(&port, &QGCAndroidSerialPort::errorOccurred); + port.close(); + QCOMPARE(errorSpy.count(), 0); + QCOMPARE(port.error(), QGCSerialPortError::NoError); +} + +void QGCAndroidSerialPortTest::_setters_whileClosed_cacheForNextOpen() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.setBaudRate(230400)); + QVERIFY(port.setDataBits(QGCDataBits::Data7)); + QVERIFY(port.setParity(QGCParity::Odd)); + QVERIFY(port.setStopBits(QGCStopBits::Two)); + + // No engine yet — values must be cached locally. + QCOMPARE(port.baudRate(), qint32(230400)); + QCOMPARE(port.dataBits(), QGCDataBits::Data7); + QCOMPARE(port.parity(), QGCParity::Odd); + QCOMPARE(port.stopBits(), QGCStopBits::Two); + + QVERIFY(port.open(QIODevice::ReadWrite)); + const auto p = g_lastMock->lastOpenParams(); + QCOMPARE(p.baudRate, 230400); + QCOMPARE(p.dataBits, 7); + QCOMPARE(p.stopBits, 2); + QCOMPARE(p.parity, static_cast(AndroidSerial::OddParity)); + + port.close(); +} + +void QGCAndroidSerialPortTest::_setters_whileOpen_applyImmediately() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + + QVERIFY(port.setBaudRate(921600)); + QVERIFY(port.setDataBits(QGCDataBits::Data8)); + QVERIFY(port.setDataTerminalReady(true)); + QVERIFY(g_lastMock->dtrAsserted()); + + QVERIFY(port.setRequestToSend(true)); + QVERIFY(g_lastMock->rtsAsserted()); + + port.close(); +} + +void QGCAndroidSerialPortTest::_testBatchedSetSerialParameters() +{ + installMockFactory(); + + QGCAndroidSerialPort port(QStringLiteral("/dev/mock0")); + QVERIFY(port.open(QIODevice::ReadWrite)); + QVERIFY(g_lastMock); + + QSignalSpy baudSpy(&port, &QGCAndroidSerialPort::baudRateChanged); + QSignalSpy dataSpy(&port, &QGCAndroidSerialPort::dataBitsChanged); + QSignalSpy stopSpy(&port, &QGCAndroidSerialPort::stopBitsChanged); + QSignalSpy paritySpy(&port, &QGCAndroidSerialPort::parityChanged); + + const int baseline = g_lastMock->setParametersCallCount(); + + QVERIFY(port.setSerialParameters(115200, QGCDataBits::Data7, + QGCStopBits::Two, QGCParity::Odd)); + + // One engine call for four parameter changes — that's the whole point. + QCOMPARE(g_lastMock->setParametersCallCount() - baseline, 1); + QCOMPARE(port.baudRate(), 115200); + QCOMPARE(port.dataBits(), QGCDataBits::Data7); + QCOMPARE(port.stopBits(), QGCStopBits::Two); + QCOMPARE(port.parity(), QGCParity::Odd); + QCOMPARE(baudSpy.count(), 1); + QCOMPARE(dataSpy.count(), 1); + QCOMPARE(stopSpy.count(), 1); + QCOMPARE(paritySpy.count(), 1); + + // No-op when nothing actually changes — no engine call, no signals. + const int afterFirst = g_lastMock->setParametersCallCount(); + QVERIFY(port.setSerialParameters(115200, QGCDataBits::Data7, + QGCStopBits::Two, QGCParity::Odd)); + QCOMPARE(g_lastMock->setParametersCallCount() - afterFirst, 0); + QCOMPARE(baudSpy.count(), 1); + + port.close(); +} diff --git a/test/Comms/Android/QGCAndroidSerialPortTest.h b/test/Comms/Android/QGCAndroidSerialPortTest.h new file mode 100644 index 000000000000..2768c6bbd858 --- /dev/null +++ b/test/Comms/Android/QGCAndroidSerialPortTest.h @@ -0,0 +1,30 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#pragma once + +#include "UnitTest.h" + +// Exercises QGCAndroidSerialPort's production logic on host via injected MockQSerialPortEngine. +// Validates open/close lifecycle, configuration caching, write paths, read fan-out, +// exception → error mapping, and re-entrancy guards — all without JNI. +class QGCAndroidSerialPortTest : public UnitTest +{ + Q_OBJECT + +private slots: + void cleanup(); + + void _open_pushesConfigToEngine(); + void _open_factoryReturningNull_fails(); + void _close_emitsAboutToCloseBeforeTeardown(); + void _close_emitsReadChannelFinished(); + void _close_clearsBuffersAndState(); + void _writeData_routesThroughEngine(); + void _dataReady_fillsReadBuffer_emitsReadyRead(); + void _exception_resourceUnavailable_setsErrorAndCloses(); + void _exception_permission_setsErrorOnly(); + void _expectClosure_suppressesResourceExceptionDuringClose(); + void _setters_whileClosed_cacheForNextOpen(); + void _setters_whileOpen_applyImmediately(); + void _testBatchedSetSerialParameters(); +}; diff --git a/test/Comms/CMakeLists.txt b/test/Comms/CMakeLists.txt index 47983d22fa92..c85112305e80 100644 --- a/test/Comms/CMakeLists.txt +++ b/test/Comms/CMakeLists.txt @@ -7,10 +7,13 @@ target_sources(${CMAKE_PROJECT_NAME} PRIVATE LinkConfigurationTest.cc LinkConfigurationTest.h + QGCSerialPortAdapterTest.cc + QGCSerialPortAdapterTest.h QGCSerialPortInfoTest.cc QGCSerialPortInfoTest.h ) target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}) +add_subdirectory(Android) add_subdirectory(Bluetooth) diff --git a/test/Comms/QGCSerialPortAdapterTest.cc b/test/Comms/QGCSerialPortAdapterTest.cc new file mode 100644 index 000000000000..f4bbd6b265de --- /dev/null +++ b/test/Comms/QGCSerialPortAdapterTest.cc @@ -0,0 +1,122 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#include "QGCSerialPortAdapterTest.h" + +#include "MockQSerialPortEngine.h" +#include "QGCAndroidSerialPort.h" +#include "QGCSerialPortAdapter.h" +#include "UnitTest.h" + +#include +#include +#include + +UT_REGISTER_TEST(QGCSerialPortAdapterTest, TestLabel::Unit, TestLabel::Comms) + +namespace { + +MockQSerialPortEngine* g_lastMock = nullptr; + +void installMockEngine() +{ + g_lastMock = nullptr; + QGCAndroidSerialPortFactory::setEngineFactory( + [](QAndroidSerialEngineReceiver* sink, QObject* owner) { + auto mock = std::make_unique(sink, owner); + g_lastMock = mock.get(); + return std::unique_ptr(std::move(mock)); + }); +} + +} // namespace + +void QGCSerialPortAdapterTest::cleanup() +{ + QGCSerialPortAdapter::setForceAndroidBackendForTests(false); + QGCAndroidSerialPortFactory::resetEngineFactory(); + g_lastMock = nullptr; + UnitTest::cleanup(); +} + +void QGCSerialPortAdapterTest::_defaultBackend_isHost() +{ + // Without the override, the host adapter wraps QSerialPort. The error() path returns + // NoError before open(), and isOpen() is false. We can't fully exercise this without + // a real port, so we just verify construction succeeds and yields a usable adapter. + QGCSerialPortAdapter adapter; + QVERIFY(!adapter.isOpen()); + QCOMPARE(adapter.error(), QGCSerialPortAdapter::NoError); +} + +void QGCSerialPortAdapterTest::_forceAndroidBackend_routesThroughMockEngine() +{ + QGCSerialPortAdapter::setForceAndroidBackendForTests(true); + installMockEngine(); + + QGCSerialPortAdapter adapter; + adapter.setPortName(QStringLiteral("/dev/mock0")); + QVERIFY(adapter.setBaudRate(115200)); + QVERIFY(adapter.setDataBits(8)); + QVERIFY(adapter.setParity(0)); + QVERIFY(adapter.setStopBits(1)); + QVERIFY(adapter.setFlowControl(0)); + + QVERIFY(adapter.open(QIODevice::ReadWrite)); + QVERIFY(adapter.isOpen()); + QVERIFY(g_lastMock); + QCOMPARE(g_lastMock->lastPortName(), QStringLiteral("/dev/mock0")); + QCOMPARE(g_lastMock->lastOpenParams().baudRate, 115200); + + adapter.close(); + QVERIFY(!adapter.isOpen()); +} + +void QGCSerialPortAdapterTest::_forceAndroidBackend_writeAndRead() +{ + QGCSerialPortAdapter::setForceAndroidBackendForTests(true); + installMockEngine(); + + QGCSerialPortAdapter adapter; + adapter.setPortName(QStringLiteral("/dev/mock0")); + QVERIFY(adapter.open(QIODevice::ReadWrite)); + + // Write side: adapter.write → QGCAndroidSerialPort.writeData → drain timer → + // engine.writeSync. Drain timer needs the event loop to fire. + const QByteArray payload("ping", 4); + QCOMPARE(adapter.write(payload.constData(), payload.size()), qint64(4)); + QTest::qWait(20); + QCOMPARE(g_lastMock->syncWrites().size(), 1); + QCOMPARE(g_lastMock->syncWrites().first(), payload); + + // Read side: mock delivers to receiver → QGCAndroidSerialPort.dataReady → + // emits readyRead → adapter forwards. + QSignalSpy readySpy(&adapter, &QGCSerialPortAdapter::readyRead); + const QByteArray rx("pong", 4); + g_lastMock->simulateRead(rx); + QCOMPARE(readySpy.count(), 1); + QCOMPARE(adapter.readAll(), rx); + + adapter.close(); +} + +void QGCSerialPortAdapterTest::_forceAndroidBackend_resourceError_propagates() +{ + QGCSerialPortAdapter::setForceAndroidBackendForTests(true); + installMockEngine(); + + QGCSerialPortAdapter adapter; + adapter.setPortName(QStringLiteral("/dev/mock0")); + QVERIFY(adapter.open(QIODevice::ReadWrite)); + + QSignalSpy errorSpy(&adapter, &QGCSerialPortAdapter::errorOccurred); + + g_lastMock->simulateException(AndroidSerial::JavaExceptionKind::Resource, + QStringLiteral("cable yanked")); + + QCOMPARE(errorSpy.count(), 1); + QCOMPARE(errorSpy.first().first().value(), + QGCSerialPortAdapter::ResourceError); + // Resource exception triggers eager close in QGCAndroidSerialPort, which the adapter + // surfaces via isOpen() going false. + QVERIFY(!adapter.isOpen()); +} diff --git a/test/Comms/QGCSerialPortAdapterTest.h b/test/Comms/QGCSerialPortAdapterTest.h new file mode 100644 index 000000000000..53bae14929fb --- /dev/null +++ b/test/Comms/QGCSerialPortAdapterTest.h @@ -0,0 +1,21 @@ +// SPDX-License-Identifier: Apache-2.0 OR GPL-3.0-only + +#pragma once + +#include "UnitTest.h" + +// Validates QGCSerialPortAdapter's runtime backend dispatch. Covers both the default +// host path (wraps QSerialPort) and the test-override path (wraps QGCAndroidSerialPort +// with an injected MockQSerialPortEngine) used by host integration tests. +class QGCSerialPortAdapterTest : public UnitTest +{ + Q_OBJECT + +private slots: + void cleanup(); + + void _defaultBackend_isHost(); + void _forceAndroidBackend_routesThroughMockEngine(); + void _forceAndroidBackend_writeAndRead(); + void _forceAndroidBackend_resourceError_propagates(); +};