From 8a5139129d2e88d0aeb6d4b071dcf3ac33fd5ef3 Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Sat, 26 Oct 2024 12:47:11 +0800 Subject: [PATCH 1/6] fix bluetooth support issue for chrome on android. and usb otg serial support for chrome on android. Update src/js/protocols/bluetooth.js Co-authored-by: Mark Haslinghuis --- src/js/DarkTheme.js | 2 +- src/js/main.js | 9 + src/js/protocols/bluetooth.js | 34 +- src/js/utils/checkBrowserCompatibilty.js | 15 +- src/js/utils/web-serial-polyfill/serial.ts | 626 +++++++++++++++++++++ 5 files changed, 675 insertions(+), 11 deletions(-) create mode 100644 src/js/utils/web-serial-polyfill/serial.ts diff --git a/src/js/DarkTheme.js b/src/js/DarkTheme.js index a9acebf85c..f721effb53 100644 --- a/src/js/DarkTheme.js +++ b/src/js/DarkTheme.js @@ -32,7 +32,7 @@ DarkTheme.apply = function() { self.applyNormal(); } - if (chrome.app.window !== undefined) { + if (chrome?.app?.window !== undefined) { windowWatcherUtil.passValue(chrome.app.window.get("receiver_msp"), 'darkTheme', isEnabled); } }); diff --git a/src/js/main.js b/src/js/main.js index 375191e78a..54ce3a82b6 100644 --- a/src/js/main.js +++ b/src/js/main.js @@ -420,6 +420,15 @@ function startProcess() { $(this).data('state', state); }); + + $("#menu_btn").on('click', function () { + $("#tab-content-container .tab_container").addClass('reveal'); + }); + + $("#tab-content-container .tab_container").on('click', function () { + $("#tab-content-container .tab_container").removeClass('reveal'); + }); + let result = getConfig('logopen'); if (result.logopen) { $("#showlog").trigger('click'); diff --git a/src/js/protocols/bluetooth.js b/src/js/protocols/bluetooth.js index 70d4142e66..92849f5af7 100644 --- a/src/js/protocols/bluetooth.js +++ b/src/js/protocols/bluetooth.js @@ -22,6 +22,7 @@ const bluetoothDevices = [ class BT extends EventTarget { constructor() { super(); + this.lastWrite=null; if (!this.bluetooth && window && window.navigator && window.navigator.bluetooth) { this.bluetooth = navigator.bluetooth; @@ -96,10 +97,14 @@ class BT extends EventTarget { } async loadDevices() { - const devices = await this.getDevices(); + try{ + const devices = await this.bluetooth.getDevices(); - this.portCounter = 1; - this.devices = devices.map(device => this.createPort(device)); + this.portCounter = 1; + this.devices = devices.map(device => this.createPort(device)); + }catch(e){ + + } } async requestPermissionDevice() { @@ -260,8 +265,12 @@ class BT extends EventTarget { } this.readCharacteristic.addEventListener('characteristicvaluechanged', this.handleNotification.bind(this)); - - return await this.readCharacteristic.readValue(); + try{ + return await this.readCharacteristic.readValue(); + }catch(e){ + console.error(e); + return; + } } handleNotification(event) { @@ -270,8 +279,9 @@ class BT extends EventTarget { for (let i = 0; i < event.target.value.byteLength; i++) { buffer[i] = event.target.value.getUint8(i); } - - this.dispatchEvent(new CustomEvent("receive", { detail: buffer })); + setTimeout(()=>{ + this.dispatchEvent(new CustomEvent("receive", { detail: buffer })); + },0); } startNotifications() { @@ -348,8 +358,14 @@ class BT extends EventTarget { this.bytesSent += data.byteLength; const dataBuffer = new Uint8Array(data); - - await this.writeCharacteristic.writeValue(dataBuffer); + try { + if (this.lastWrite){ + await this.lastWrite; + } + } catch(error) { + console.error(error); + } + this.lastWrite = this.writeCharacteristic.writeValueWithoutResponse(dataBuffer); return { bytesSent: data.byteLength, diff --git a/src/js/utils/checkBrowserCompatibilty.js b/src/js/utils/checkBrowserCompatibilty.js index b5f6beda87..b209370158 100644 --- a/src/js/utils/checkBrowserCompatibilty.js +++ b/src/js/utils/checkBrowserCompatibilty.js @@ -1,3 +1,5 @@ +import { serial as serialPolyfill } from './web-serial-polyfill/serial.ts'; + export function isChromium() { // https://developer.mozilla.org/en-US/docs/Web/HTTP/Browser_detection_using_the_user_agent if (!navigator.userAgentData) { @@ -13,7 +15,18 @@ export function isChromium() { } export function checkBrowserCompatibility() { - const compatible = "serial" in navigator; + let compatible = "serial" in navigator; + if (!compatible) { + if('usb' in navigator && + !('brave' in navigator) + ) { + navigator.serial = serialPolyfill; + } + + if(navigator?.serial || navigator?.bluetooth){ + compatible = true; + } + } if (isChromium() && compatible) { return true; diff --git a/src/js/utils/web-serial-polyfill/serial.ts b/src/js/utils/web-serial-polyfill/serial.ts new file mode 100644 index 0000000000..4a01ec93d1 --- /dev/null +++ b/src/js/utils/web-serial-polyfill/serial.ts @@ -0,0 +1,626 @@ +/* eslint-disable */ +/* + * Copyright 2019 Google LLC + * + * Licensed under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in + * compliance with the License. You may obtain a copy of + * the License at + * + * https://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in + * writing, software distributed under the License is + * distributed on an "AS IS" BASIS, WITHOUT WARRANTIES + * OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing + * permissions and limitations under the License. + */ +'use strict'; + +type ParityType = 'none' | 'even' | 'odd' | 'mark' | 'space'; + +interface SerialOptions { + baudRate: number; + dataBits: number; + stopBits: number; + parity: ParityType; + bufferSize: number; + rtscts: boolean; + xon: boolean; + xoff: boolean; + xany: boolean; +} + +interface SerialOutputSignals { + dtr?: boolean; + rts?: boolean; + brk?: boolean; +} + +export enum SerialPolyfillProtocol { + UsbCdcAcm, +} + +export interface SerialPolyfillOptions { + protocol?: SerialPolyfillProtocol; + usbControlInterfaceClass?: number; + usbTransferInterfaceClass?: number; +} + +export interface SerialPortFilter { + usbVendorId?: number; + usbProductId?: number; +} + +export interface SerialPortRequestOptions { + filters?: Array; + polyfillOptions?: SerialPolyfillOptions; +} + +const kSetLineCoding = 0x20; +const kSetControlLineState = 0x22; +const kSendBreak = 0x23; + +const kDefaultSerialOptions: SerialOptions = { + baudRate: 115200, + dataBits: 8, + stopBits: 1, + parity: 'none', + bufferSize: 255, + rtscts: false, + xon: false, + xoff: false, + xany: false, +}; +const kAcceptableDataBits = [16, 8, 7, 6, 5]; +const kAcceptableStopBits = [1, 2]; +const kAcceptableParity = ['none', 'even', 'mark', 'odd', 'space']; + +const kParityIndexMapping: ParityType[] = + ['none', 'odd', 'even', 'mark', 'space']; +const kStopBitsIndexMapping = [1, 1.5, 2]; + +const kDefaultPolyfillOptions = { + protocol: SerialPolyfillProtocol.UsbCdcAcm, + usbControlInterfaceClass: 2, + usbTransferInterfaceClass: 10, +}; + +/** + * Utility function to get the interface implementing a desired class. + * @param {USBDevice} device The USB device. + * @param {number} classCode The desired interface class. + * @return {USBInterface} The first interface found that implements the desired + * class. + * @throws TypeError if no interface is found. + */ +function findInterface(device: USBDevice, classCode: number): USBInterface { + const configuration = device.configurations[0]; + for (const iface of configuration.interfaces) { + const alternate = iface.alternates[0]; + if (alternate.interfaceClass === classCode) { + return iface; + } + } + throw new TypeError(`Unable to find interface with class ${classCode}.`); +} + +/** + * Utility function to get an endpoint with a particular direction. + * @param {USBInterface} iface The interface to search. + * @param {USBDirection} direction The desired transfer direction. + * @return {USBEndpoint} The first endpoint with the desired transfer direction. + * @throws TypeError if no endpoint is found. + */ +function findEndpoint(iface: USBInterface, direction: USBDirection): + USBEndpoint { + const alternate = iface.alternates[0]; + for (const endpoint of alternate.endpoints) { + if (endpoint.direction == direction) { + return endpoint; + } + } + throw new TypeError(`Interface ${iface.interfaceNumber} does not have an ` + + `${direction} endpoint.`); +} + +/** + * Implementation of the underlying source API[1] which reads data from a USB + * endpoint. This can be used to construct a ReadableStream. + * + * [1]: https://streams.spec.whatwg.org/#underlying-source-api + */ +class UsbEndpointUnderlyingSource implements UnderlyingSource { + private device_: USBDevice; + private endpoint_: USBEndpoint; + private onError_: () => void; + + /** + * Constructs a new UnderlyingSource that will pull data from the specified + * endpoint on the given USB device. + * + * @param {USBDevice} device + * @param {USBEndpoint} endpoint + * @param {function} onError function to be called on error + */ + constructor(device: USBDevice, endpoint: USBEndpoint, onError: () => void) { + this.device_ = device; + this.endpoint_ = endpoint; + this.onError_ = onError; + } + + /** + * Reads a chunk of data from the device. + * + * @param {ReadableStreamDefaultController} controller + */ + async pull(controller: ReadableStreamDefaultController): Promise { + const chunkSize = controller.desiredSize || 64; + try { + for (; ;) { + let result = await this.device_.transferIn(this.endpoint_.endpointNumber, chunkSize); + if (result?.data && result.data.byteLength > 0) { + controller.enqueue(result.data); + break; + } else { + await new Promise((res, _) => setTimeout(res, 10, 0)); + } + } + } + catch (error) { + controller.error(error.toString()); + this.onError_(); + } + } +} + +/** + * Implementation of the underlying sink API[2] which writes data to a USB + * endpoint. This can be used to construct a WritableStream. + * + * [2]: https://streams.spec.whatwg.org/#underlying-sink-api + */ +class UsbEndpointUnderlyingSink implements UnderlyingSink { + private device_: USBDevice; + private endpoint_: USBEndpoint; + private onError_: () => void; + + /** + * Constructs a new UnderlyingSink that will write data to the specified + * endpoint on the given USB device. + * + * @param {USBDevice} device + * @param {USBEndpoint} endpoint + * @param {function} onError function to be called on error + */ + constructor(device: USBDevice, endpoint: USBEndpoint, onError: () => void) { + this.device_ = device; + this.endpoint_ = endpoint; + this.onError_ = onError; + } + + /** + * Writes a chunk to the device. + * + * @param {Uint8Array} chunk + * @param {WritableStreamDefaultController} controller + */ + async write( + chunk: Uint8Array, + controller: WritableStreamDefaultController): Promise { + try { + const result = + await this.device_.transferOut(this.endpoint_.endpointNumber, chunk); + if (result.status != 'ok') { + controller.error(result.status); + this.onError_(); + } + } catch (error) { + controller.error(error.toString()); + this.onError_(); + } + } +} + +/** a class used to control serial devices over WebUSB */ +export class SerialPort { + private polyfillOptions_: SerialPolyfillOptions; + private device_: USBDevice; + private controlInterface_: USBInterface; + private transferInterface_: USBInterface; + private inEndpoint_: USBEndpoint; + private outEndpoint_: USBEndpoint; + + private serialOptions_: SerialOptions; + private readable_: ReadableStream | null; + private writable_: WritableStream | null; + private outputSignals_: SerialOutputSignals; + + /** + * constructor taking a WebUSB device that creates a SerialPort instance. + * @param {USBDevice} device A device acquired from the WebUSB API + * @param {SerialPolyfillOptions} polyfillOptions Optional options to + * configure the polyfill. + */ + public constructor( + device: USBDevice, + polyfillOptions?: SerialPolyfillOptions) { + this.polyfillOptions_ = {...kDefaultPolyfillOptions, ...polyfillOptions}; + this.outputSignals_ = { + dtr: false, + rts: false, + brk: false, + }; + + this.device_ = device; + this.controlInterface_ = findInterface( + this.device_, + this.polyfillOptions_.usbControlInterfaceClass as number); + this.transferInterface_ = findInterface( + this.device_, + this.polyfillOptions_.usbTransferInterfaceClass as number); + this.inEndpoint_ = findEndpoint(this.transferInterface_, 'in'); + this.outEndpoint_ = findEndpoint(this.transferInterface_, 'out'); + } + + /** + * Getter for the readable attribute. Constructs a new ReadableStream as + * necessary. + * @return {ReadableStream} the current readable stream + */ + public get readable(): ReadableStream | null { + if (!this.readable_ && this.device_.opened) { + this.readable_ = new ReadableStream( + new UsbEndpointUnderlyingSource( + this.device_, this.inEndpoint_, () => { + this.readable_ = null; + }), + new ByteLengthQueuingStrategy({ + highWaterMark: this.serialOptions_.bufferSize, + })); + } + return this.readable_; + } + + /** + * Getter for the writable attribute. Constructs a new WritableStream as + * necessary. + * @return {WritableStream} the current writable stream + */ + public get writable(): WritableStream | null { + if (!this.writable_ && this.device_.opened) { + this.writable_ = new WritableStream( + new UsbEndpointUnderlyingSink( + this.device_, this.outEndpoint_, () => { + this.writable_ = null; + }), + new ByteLengthQueuingStrategy({ + highWaterMark: this.serialOptions_.bufferSize, + })); + } + return this.writable_; + } + + /** + * a function that opens the device and claims all interfaces needed to + * control and communicate to and from the serial device + * @param {SerialOptions} options Optional object containing serial options + * @return {Promise} A promise that will resolve when device is ready + * for communication + */ + public async open(options?: SerialOptions): Promise { + this.serialOptions_ = {...kDefaultSerialOptions, ...options}; + this.validateOptions(); + + try { + await this.device_.open(); + if (this.device_.configuration === null) { + await this.device_.selectConfiguration(1); + } + + await this.device_.claimInterface(this.controlInterface_.interfaceNumber); + if (this.controlInterface_ !== this.transferInterface_) { + await this.device_.claimInterface( + this.transferInterface_.interfaceNumber); + } + + await this.setLineCoding(); + await this.setSignals({dtr: true}); + } catch (error) { + if (this.device_.opened) { + await this.device_.close(); + } + throw new Error('Error setting up device: ' + error.toString()); + } + } + + /** + * Closes the port. + * + * @return {Promise} A promise that will resolve when the port is + * closed. + */ + public async close(): Promise { + const promises = []; + if (this.readable_) { + promises.push(this.readable_.cancel()); + } + if (this.writable_) { + promises.push(this.writable_.abort()); + } + await Promise.all(promises); + this.readable_ = null; + this.writable_ = null; + if (this.device_.opened) { + await this.setSignals({dtr: false, rts: false}); + await this.device_.close(); + } + } + + /** + * A function that returns properties of the device. + * @return {SerialPortInfo} Device properties. + */ + public getInfo(): SerialPortInfo { + return { + usbVendorId: this.device_.vendorId, + usbProductId: this.device_.productId, + }; + } + + /** + * A function used to change the serial settings of the device + * @param {object} options the object which carries serial settings data + * @return {Promise} A promise that will resolve when the options are + * set + */ + public reconfigure(options: SerialOptions): Promise { + this.serialOptions_ = {...this.serialOptions_, ...options}; + this.validateOptions(); + return this.setLineCoding(); + } + + /** + * Sets control signal state for the port. + * @param {SerialOutputSignals} signals The signals to enable or disable. + * @return {Promise} a promise that is resolved when the signal state + * has been changed. + */ + public async setSignals(signals: SerialOutputSignals): Promise { + this.outputSignals_ = {...this.outputSignals_, ...signals}; + + if (signals.dtr !== undefined || signals.rts !== undefined) { + // The Set_Control_Line_State command expects a bitmap containing the + // values of all output signals that should be enabled or disabled. + // + // Ref: USB CDC specification version 1.1 §6.2.14. + const value = (this.outputSignals_.dtr ? 1 << 0 : 0) | + (this.outputSignals_.rts ? 1 << 1 : 0); + + await this.device_.controlTransferOut({ + 'requestType': 'class', + 'recipient': 'interface', + 'request': kSetControlLineState, + 'value': value, + 'index': this.controlInterface_.interfaceNumber, + }); + } + + if (signals.brk !== undefined) { + // The SendBreak command expects to be given a duration for how long the + // break signal should be asserted. Passing 0xFFFF enables the signal + // until 0x0000 is send. + // + // Ref: USB CDC specification version 1.1 §6.2.15. + const value = this.outputSignals_.brk ? 0xFFFF : 0x0000; + + await this.device_.controlTransferOut({ + 'requestType': 'class', + 'recipient': 'interface', + 'request': kSendBreak, + 'value': value, + 'index': this.controlInterface_.interfaceNumber, + }); + } + } + + /** + * Checks the serial options for validity and throws an error if it is + * not valid + */ + private validateOptions(): void { + if (!this.isValidBaudRate(this.serialOptions_.baudRate)) { + throw new RangeError('invalid Baud Rate ' + this.serialOptions_.baudRate); + } + + if (!this.isValidDataBits(this.serialOptions_.dataBits)) { + throw new RangeError('invalid dataBits ' + this.serialOptions_.dataBits); + } + + if (!this.isValidStopBits(this.serialOptions_.stopBits)) { + throw new RangeError('invalid stopBits ' + this.serialOptions_.stopBits); + } + + if (!this.isValidParity(this.serialOptions_.parity)) { + throw new RangeError('invalid parity ' + this.serialOptions_.parity); + } + } + + /** + * Checks the baud rate for validity + * @param {number} baudRate the baud rate to check + * @return {boolean} A boolean that reflects whether the baud rate is valid + */ + private isValidBaudRate(baudRate: number): boolean { + return baudRate % 1 === 0; + } + + /** + * Checks the data bits for validity + * @param {number} dataBits the data bits to check + * @return {boolean} A boolean that reflects whether the data bits setting is + * valid + */ + private isValidDataBits(dataBits: number): boolean { + return kAcceptableDataBits.includes(dataBits); + } + + /** + * Checks the stop bits for validity + * @param {number} stopBits the stop bits to check + * @return {boolean} A boolean that reflects whether the stop bits setting is + * valid + */ + private isValidStopBits(stopBits: number): boolean { + return kAcceptableStopBits.includes(stopBits); + } + + /** + * Checks the parity for validity + * @param {string} parity the parity to check + * @return {boolean} A boolean that reflects whether the parity is valid + */ + private isValidParity(parity: ParityType): boolean { + return kAcceptableParity.includes(parity); + } + + /** + * sends the options alog the control interface to set them on the device + * @return {Promise} a promise that will resolve when the options are set + */ + private async setLineCoding(): Promise { + // Ref: USB CDC specification version 1.1 §6.2.12. + const buffer = new ArrayBuffer(7); + const view = new DataView(buffer); + view.setUint32(0, this.serialOptions_.baudRate, true); + view.setUint8( + 4, kStopBitsIndexMapping.indexOf(this.serialOptions_.stopBits)); + view.setUint8(5, kParityIndexMapping.indexOf(this.serialOptions_.parity)); + view.setUint8(6, this.serialOptions_.dataBits); + + const result = await this.device_.controlTransferOut({ + 'requestType': 'class', + 'recipient': 'interface', + 'request': kSetLineCoding, + 'value': 0x00, + 'index': this.controlInterface_.interfaceNumber, + }, buffer); + if (result.status != 'ok') { + throw new DOMException('NetworkError', 'Failed to set line coding.'); + } + } + + /** + * Takes in an Array Buffer that contains Line Coding according to the USB + * CDC spec + * @param {ArrayBuffer} buffer The data structured accoding to the spec + * @return {object} The options + */ + private readLineCoding(buffer: ArrayBuffer): SerialOptions { + const options: SerialOptions = this.serialOptions_; + const view = new DataView(buffer); + options.baudRate = view.getUint32(0, true); + options.stopBits = view.getUint8(4) < kStopBitsIndexMapping.length ? + kStopBitsIndexMapping[view.getUint8(4)] : + 1; + options.parity = view.getUint8(5) < kParityIndexMapping.length ? + kParityIndexMapping[view.getUint8(5)] : + 'none'; + options.dataBits = view.getUint8(6); + return options; + } +} + +/** implementation of the global navigator.serial object */ +class Serial { + /** + * Requests permission to access a new port. + * + * @param {SerialPortRequestOptions} options + * @param {SerialPolyfillOptions} polyfillOptions + * @return {Promise} + */ + async requestPort( + options?: SerialPortRequestOptions, + polyfillOptions?: SerialPolyfillOptions): Promise { + polyfillOptions = {...kDefaultPolyfillOptions, ...polyfillOptions}; + + const usbFilters: USBDeviceFilter[] = []; + if (options && options.filters) { + for (const filter of options.filters) { + const usbFilter: USBDeviceFilter = { + classCode: polyfillOptions.usbControlInterfaceClass, + }; + if (filter.usbVendorId !== undefined) { + usbFilter.vendorId = filter.usbVendorId; + } + if (filter.usbProductId !== undefined) { + usbFilter.productId = filter.usbProductId; + } + usbFilters.push(usbFilter); + } + } + + if (usbFilters.length === 0) { + usbFilters.push({ + classCode: polyfillOptions.usbControlInterfaceClass, + }); + } + + const device = await navigator.usb.requestDevice({'filters': usbFilters}); + const port = new SerialPort(device, polyfillOptions); + return port; + } + + /** + * Get the set of currently available ports. + * + * @param {SerialPolyfillOptions} polyfillOptions Polyfill configuration that + * should be applied to these ports. + * @return {Promise} a promise that is resolved with a list of + * ports. + */ + async getPorts(polyfillOptions?: SerialPolyfillOptions): + Promise { + polyfillOptions = {...kDefaultPolyfillOptions, ...polyfillOptions}; + + const devices = await navigator.usb.getDevices(); + const ports: SerialPort[] = []; + devices.forEach((device) => { + try { + const port = new SerialPort(device, polyfillOptions); + ports.push(port); + } catch (e) { + // Skip unrecognized port. + } + }); + return ports; + } + + /** + * Attach an event listener. + * + * @param {string} event the event to listen for. + * @param {Function} handleEvent the function to be triggered on the event. + */ + addEventListener(event: 'connect' | 'disconnect', + handleEvent: EventListener | EventListenerObject | null): void { + navigator.usb.addEventListener(event, handleEvent); + } + + /** + * Remove an event listener. + * + * @param {string} event the event for which the listener should be removed. + * @param {Function} handleEvent the handler to be removed. + */ + removeEventListener(event: 'connect' | 'disconnect', + handleEvent: EventListener | EventListenerObject | null): + void { + navigator.usb.removeEventListener(event, handleEvent); + } +} + +/* an object to be used for starting the serial workflow */ +export const serial = new Serial(); From 3f6d9744b700cc4abb74534d9ee5914d500d6212 Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Mon, 28 Oct 2024 19:46:21 +0800 Subject: [PATCH 2/6] Apply suggestions from code review Co-authored-by: Mark Haslinghuis --- src/js/protocols/bluetooth.js | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/js/protocols/bluetooth.js b/src/js/protocols/bluetooth.js index 92849f5af7..13918af456 100644 --- a/src/js/protocols/bluetooth.js +++ b/src/js/protocols/bluetooth.js @@ -22,7 +22,7 @@ const bluetoothDevices = [ class BT extends EventTarget { constructor() { super(); - this.lastWrite=null; + this.lastWrite = null; if (!this.bluetooth && window && window.navigator && window.navigator.bluetooth) { this.bluetooth = navigator.bluetooth; @@ -97,12 +97,12 @@ class BT extends EventTarget { } async loadDevices() { - try{ + try { const devices = await this.bluetooth.getDevices(); this.portCounter = 1; this.devices = devices.map(device => this.createPort(device)); - }catch(e){ + } catch(e) { } } @@ -265,9 +265,9 @@ class BT extends EventTarget { } this.readCharacteristic.addEventListener('characteristicvaluechanged', this.handleNotification.bind(this)); - try{ + try { return await this.readCharacteristic.readValue(); - }catch(e){ + } catch(e) { console.error(e); return; } From 903d268a5a12d5ca28c65a81b8c6b7de140f5959 Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Tue, 29 Oct 2024 08:57:25 +0800 Subject: [PATCH 3/6] fix serial polyfill issue --- src/js/webSerial.js | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/js/webSerial.js b/src/js/webSerial.js index 0492c1cfe2..f39ace6ae2 100644 --- a/src/js/webSerial.js +++ b/src/js/webSerial.js @@ -142,8 +142,9 @@ class WebSerial extends EventTarget { this.bytesSent = 0; this.failed = 0; this.openRequested = false; - - this.port.addEventListener("disconnect", this.handleDisconnect.bind(this)); + if(this.port.addEventListener){ + this.port.addEventListener("disconnect", this.handleDisconnect.bind(this)); + } this.addEventListener("receive", this.handleReceiveBytes); console.log( From da040e1e4876b9c6967dded979414085f608eaf0 Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Tue, 29 Oct 2024 09:13:33 +0800 Subject: [PATCH 4/6] Update src/js/utils/checkBrowserCompatibilty.js Co-authored-by: Mark Haslinghuis --- src/js/utils/checkBrowserCompatibilty.js | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/src/js/utils/checkBrowserCompatibilty.js b/src/js/utils/checkBrowserCompatibilty.js index b209370158..9e0597feea 100644 --- a/src/js/utils/checkBrowserCompatibilty.js +++ b/src/js/utils/checkBrowserCompatibilty.js @@ -16,16 +16,10 @@ export function isChromium() { export function checkBrowserCompatibility() { let compatible = "serial" in navigator; - if (!compatible) { - if('usb' in navigator && - !('brave' in navigator) - ) { - navigator.serial = serialPolyfill; - } - if(navigator?.serial || navigator?.bluetooth){ - compatible = true; - } + if (!compatible && 'usb' in navigator && !('brave' in navigator)) { + navigator.serial = serialPolyfill; + compatible = true; } if (isChromium() && compatible) { From bd05dde98c3a689cddbad4639ea61468668f934a Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Sun, 3 Nov 2024 13:14:41 +0800 Subject: [PATCH 5/6] Update src/js/webSerial.js Co-authored-by: Mark Haslinghuis --- src/js/webSerial.js | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/js/webSerial.js b/src/js/webSerial.js index f39ace6ae2..413930a6f4 100644 --- a/src/js/webSerial.js +++ b/src/js/webSerial.js @@ -142,7 +142,7 @@ class WebSerial extends EventTarget { this.bytesSent = 0; this.failed = 0; this.openRequested = false; - if(this.port.addEventListener){ + if (this.port.addEventListener) { this.port.addEventListener("disconnect", this.handleDisconnect.bind(this)); } this.addEventListener("receive", this.handleReceiveBytes); From b11c3210a3f0ffc10b7896229135ae1e562e7a54 Mon Sep 17 00:00:00 2001 From: kikoqiu Date: Tue, 19 Nov 2024 15:18:47 +0800 Subject: [PATCH 6/6] Update bluetooth.js --- src/js/protocols/bluetooth.js | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/js/protocols/bluetooth.js b/src/js/protocols/bluetooth.js index 13918af456..722f30f410 100644 --- a/src/js/protocols/bluetooth.js +++ b/src/js/protocols/bluetooth.js @@ -365,7 +365,7 @@ class BT extends EventTarget { } catch(error) { console.error(error); } - this.lastWrite = this.writeCharacteristic.writeValueWithoutResponse(dataBuffer); + this.lastWrite = this.writeCharacteristic.writeValueWithResponse(dataBuffer); return { bytesSent: data.byteLength,