mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-19 14:25:14 +03:00
parent
44976bd199
commit
5af689616f
3 changed files with 124 additions and 120 deletions
|
@ -1,17 +1,33 @@
|
||||||
import { webSerialDevices, vendorIdNames } from "./devices";
|
import { webSerialDevices, vendorIdNames } from "./devices";
|
||||||
import { checkBrowserCompatibility } from "../utils/checkBrowserCompatibilty";
|
import { checkBrowserCompatibility } from "../utils/checkBrowserCompatibilty";
|
||||||
|
|
||||||
|
const logHead = "[SERIAL]";
|
||||||
|
|
||||||
async function* streamAsyncIterable(reader, keepReadingFlag) {
|
async function* streamAsyncIterable(reader, keepReadingFlag) {
|
||||||
try {
|
try {
|
||||||
while (keepReadingFlag()) {
|
while (keepReadingFlag()) {
|
||||||
const { done, value } = await reader.read();
|
try {
|
||||||
if (done) {
|
const { done, value } = await reader.read();
|
||||||
return;
|
if (done) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
yield value;
|
||||||
|
} catch (error) {
|
||||||
|
console.warn(`${logHead} Read error in streamAsyncIterable:`, error);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
yield value;
|
|
||||||
}
|
}
|
||||||
} finally {
|
} finally {
|
||||||
reader.releaseLock();
|
// Only release the lock if we still have the reader and it hasn't been released
|
||||||
|
try {
|
||||||
|
// Always attempt once; spec allows releasing even if the stream
|
||||||
|
// is already closed. `locked` is the boolean we can trust.
|
||||||
|
if (reader?.locked) {
|
||||||
|
reader.releaseLock();
|
||||||
|
}
|
||||||
|
} catch (error) {
|
||||||
|
console.warn(`${logHead} Error releasing reader lock:`, error);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -36,8 +52,6 @@ class WebSerial extends EventTarget {
|
||||||
this.bytesReceived = 0;
|
this.bytesReceived = 0;
|
||||||
this.failed = 0;
|
this.failed = 0;
|
||||||
|
|
||||||
this.logHead = "[SERIAL]";
|
|
||||||
|
|
||||||
this.portCounter = 0;
|
this.portCounter = 0;
|
||||||
this.ports = [];
|
this.ports = [];
|
||||||
this.port = null;
|
this.port = null;
|
||||||
|
@ -78,7 +92,7 @@ class WebSerial extends EventTarget {
|
||||||
}
|
}
|
||||||
|
|
||||||
handleDisconnect() {
|
handleDisconnect() {
|
||||||
console.log(`${this.logHead} Device disconnected externally`);
|
console.log(`${logHead} Device disconnected externally`);
|
||||||
this.disconnect();
|
this.disconnect();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -102,7 +116,7 @@ class WebSerial extends EventTarget {
|
||||||
|
|
||||||
async loadDevices() {
|
async loadDevices() {
|
||||||
if (!navigator.serial) {
|
if (!navigator.serial) {
|
||||||
console.error(`${this.logHead} Web Serial API not available`);
|
console.error(`${logHead} Web Serial API not available`);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -111,13 +125,13 @@ class WebSerial extends EventTarget {
|
||||||
this.portCounter = 1;
|
this.portCounter = 1;
|
||||||
this.ports = ports.map((port) => this.createPort(port));
|
this.ports = ports.map((port) => this.createPort(port));
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error loading devices:`, error);
|
console.error(`${logHead} Error loading devices:`, error);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
async requestPermissionDevice(showAllSerialDevices = false) {
|
async requestPermissionDevice(showAllSerialDevices = false) {
|
||||||
if (!navigator.serial) {
|
if (!navigator.serial) {
|
||||||
console.error(`${this.logHead} Web Serial API not available`);
|
console.error(`${logHead} Web Serial API not available`);
|
||||||
return null;
|
return null;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -132,9 +146,9 @@ class WebSerial extends EventTarget {
|
||||||
if (!newPermissionPort) {
|
if (!newPermissionPort) {
|
||||||
newPermissionPort = this.handleNewDevice(userSelectedPort);
|
newPermissionPort = this.handleNewDevice(userSelectedPort);
|
||||||
}
|
}
|
||||||
console.info(`${this.logHead} User selected SERIAL device from permissions:`, newPermissionPort.path);
|
console.info(`${logHead} User selected SERIAL device from permissions:`, newPermissionPort.path);
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} User didn't select any SERIAL device when requesting permission:`, error);
|
console.error(`${logHead} User didn't select any SERIAL device when requesting permission:`, error);
|
||||||
}
|
}
|
||||||
return newPermissionPort;
|
return newPermissionPort;
|
||||||
}
|
}
|
||||||
|
@ -146,7 +160,7 @@ class WebSerial extends EventTarget {
|
||||||
async connect(path, options = { baudRate: 115200 }) {
|
async connect(path, options = { baudRate: 115200 }) {
|
||||||
// Prevent double connections
|
// Prevent double connections
|
||||||
if (this.connected) {
|
if (this.connected) {
|
||||||
console.log(`${this.logHead} Already connected, not connecting again`);
|
console.log(`${logHead} Already connected, not connecting again`);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -156,7 +170,7 @@ class WebSerial extends EventTarget {
|
||||||
try {
|
try {
|
||||||
const device = this.ports.find((device) => device.path === path);
|
const device = this.ports.find((device) => device.path === path);
|
||||||
if (!device) {
|
if (!device) {
|
||||||
console.error(`${this.logHead} Device not found:`, path);
|
console.error(`${logHead} Device not found:`, path);
|
||||||
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -182,9 +196,7 @@ class WebSerial extends EventTarget {
|
||||||
this.port.addEventListener("disconnect", this.handleDisconnect);
|
this.port.addEventListener("disconnect", this.handleDisconnect);
|
||||||
this.addEventListener("receive", this.handleReceiveBytes);
|
this.addEventListener("receive", this.handleReceiveBytes);
|
||||||
|
|
||||||
console.log(
|
console.log(`${logHead} Connection opened with ID: ${this.connectionId}, Baud: ${options.baudRate}`);
|
||||||
`${this.logHead} Connection opened with ID: ${this.connectionId}, Baud: ${options.baudRate}`,
|
|
||||||
);
|
|
||||||
|
|
||||||
this.dispatchEvent(new CustomEvent("connect", { detail: connectionInfo }));
|
this.dispatchEvent(new CustomEvent("connect", { detail: connectionInfo }));
|
||||||
|
|
||||||
|
@ -196,9 +208,7 @@ class WebSerial extends EventTarget {
|
||||||
} else if (connectionInfo && this.openCanceled) {
|
} else if (connectionInfo && this.openCanceled) {
|
||||||
this.connectionId = path;
|
this.connectionId = path;
|
||||||
|
|
||||||
console.log(
|
console.log(`${logHead} Connection opened with ID: ${path}, but request was canceled, disconnecting`);
|
||||||
`${this.logHead} Connection opened with ID: ${path}, but request was canceled, disconnecting`,
|
|
||||||
);
|
|
||||||
// some bluetooth dongles/dongle drivers really doesn't like to be closed instantly, adding a small delay
|
// some bluetooth dongles/dongle drivers really doesn't like to be closed instantly, adding a small delay
|
||||||
setTimeout(() => {
|
setTimeout(() => {
|
||||||
this.openRequested = false;
|
this.openRequested = false;
|
||||||
|
@ -210,12 +220,12 @@ class WebSerial extends EventTarget {
|
||||||
return false;
|
return false;
|
||||||
} else {
|
} else {
|
||||||
this.openRequested = false;
|
this.openRequested = false;
|
||||||
console.log(`${this.logHead} Failed to open serial port`);
|
console.log(`${logHead} Failed to open serial port`);
|
||||||
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error connecting:`, error);
|
console.error(`${logHead} Error connecting:`, error);
|
||||||
this.openRequested = false;
|
this.openRequested = false;
|
||||||
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
this.dispatchEvent(new CustomEvent("connect", { detail: false }));
|
||||||
return false;
|
return false;
|
||||||
|
@ -228,67 +238,76 @@ class WebSerial extends EventTarget {
|
||||||
this.dispatchEvent(new CustomEvent("receive", { detail: value }));
|
this.dispatchEvent(new CustomEvent("receive", { detail: value }));
|
||||||
}
|
}
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error reading:`, error);
|
console.error(`${logHead} Error reading:`, error);
|
||||||
if (this.connected) {
|
if (this.connected) {
|
||||||
this.disconnect();
|
this.disconnect();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
async disconnect(callback) {
|
// Update disconnect method
|
||||||
// If already disconnected, just call callback and return
|
async disconnect() {
|
||||||
|
// If already disconnected, just return
|
||||||
if (!this.connected) {
|
if (!this.connected) {
|
||||||
if (callback) {
|
|
||||||
try {
|
|
||||||
callback(true);
|
|
||||||
} catch (error) {
|
|
||||||
console.error(`${this.logHead} Error calling disconnect callback:`, error);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Mark as disconnected immediately to prevent race conditions
|
// Mark as disconnected immediately to prevent race conditions
|
||||||
this.connected = false;
|
this.connected = false;
|
||||||
this.transmitting = false;
|
this.transmitting = false;
|
||||||
|
|
||||||
|
// Signal the read loop to stop BEFORE attempting cleanup
|
||||||
this.reading = false;
|
this.reading = false;
|
||||||
|
|
||||||
// if we are already closing, don't do it again
|
// If already closing, don't do it again
|
||||||
if (this.closeRequested) {
|
if (this.closeRequested) {
|
||||||
if (callback) {
|
|
||||||
try {
|
|
||||||
callback(true);
|
|
||||||
} catch (error) {
|
|
||||||
console.error(`${this.logHead} Error calling disconnect callback:`, error);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
this.closeRequested = true;
|
this.closeRequested = true;
|
||||||
|
|
||||||
try {
|
try {
|
||||||
|
// Remove event listeners first
|
||||||
this.removeEventListener("receive", this.handleReceiveBytes);
|
this.removeEventListener("receive", this.handleReceiveBytes);
|
||||||
|
|
||||||
|
// Small delay to allow ongoing operations to notice connection state change
|
||||||
|
await new Promise((resolve) => setTimeout(resolve, 50));
|
||||||
|
|
||||||
|
// Cancel reader first if it exists - this doesn't release the lock
|
||||||
if (this.reader) {
|
if (this.reader) {
|
||||||
await this.reader.cancel();
|
try {
|
||||||
await this.reader.releaseLock();
|
await this.reader.cancel();
|
||||||
this.reader = null;
|
} catch (e) {
|
||||||
|
console.warn(`${logHead} Reader cancel error (can be ignored):`, e);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Don't try to release the reader lock - streamAsyncIterable will handle it
|
||||||
|
this.reader = null;
|
||||||
|
|
||||||
|
// Release writer lock if it exists
|
||||||
if (this.writer) {
|
if (this.writer) {
|
||||||
await this.writer.releaseLock();
|
try {
|
||||||
|
this.writer.releaseLock();
|
||||||
|
} catch (e) {
|
||||||
|
console.warn(`${logHead} Writer release error (can be ignored):`, e);
|
||||||
|
}
|
||||||
this.writer = null;
|
this.writer = null;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Close the port
|
||||||
if (this.port) {
|
if (this.port) {
|
||||||
this.port.removeEventListener("disconnect", this.handleDisconnect);
|
this.port.removeEventListener("disconnect", this.handleDisconnect);
|
||||||
await this.port.close();
|
try {
|
||||||
|
await this.port.close();
|
||||||
|
} catch (e) {
|
||||||
|
console.warn(`${logHead} Port already closed or error during close:`, e);
|
||||||
|
}
|
||||||
this.port = null;
|
this.port = null;
|
||||||
}
|
}
|
||||||
|
|
||||||
console.log(
|
console.log(
|
||||||
`${this.logHead} Connection with ID: ${this.connectionId} closed, Sent: ${this.bytesSent} bytes, Received: ${this.bytesReceived} bytes`,
|
`${logHead} Connection with ID: ${this.connectionId} closed, Sent: ${this.bytesSent} bytes, Received: ${this.bytesReceived} bytes`,
|
||||||
);
|
);
|
||||||
|
|
||||||
this.connectionId = false;
|
this.connectionId = false;
|
||||||
|
@ -296,33 +315,11 @@ class WebSerial extends EventTarget {
|
||||||
this.closeRequested = false;
|
this.closeRequested = false;
|
||||||
|
|
||||||
this.dispatchEvent(new CustomEvent("disconnect", { detail: true }));
|
this.dispatchEvent(new CustomEvent("disconnect", { detail: true }));
|
||||||
|
|
||||||
if (callback) {
|
|
||||||
try {
|
|
||||||
callback(true);
|
|
||||||
} catch (error) {
|
|
||||||
console.error(`${this.logHead} Error calling disconnect callback:`, error);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error disconnecting:`, error);
|
console.error(`${logHead} Error disconnecting:`, error);
|
||||||
console.error(
|
|
||||||
`${this.logHead} Failed to close connection with ID: ${this.connectionId} closed, Sent: ${this.bytesSent} bytes, Received: ${this.bytesReceived} bytes`,
|
|
||||||
);
|
|
||||||
|
|
||||||
this.closeRequested = false;
|
this.closeRequested = false;
|
||||||
this.dispatchEvent(new CustomEvent("disconnect", { detail: false }));
|
this.dispatchEvent(new CustomEvent("disconnect", { detail: false }));
|
||||||
|
|
||||||
if (callback) {
|
|
||||||
try {
|
|
||||||
callback(false);
|
|
||||||
} catch (error) {
|
|
||||||
console.error(`${this.logHead} Error calling disconnect callback:`, error);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
} finally {
|
} finally {
|
||||||
if (this.openCanceled) {
|
if (this.openCanceled) {
|
||||||
|
@ -333,7 +330,7 @@ class WebSerial extends EventTarget {
|
||||||
|
|
||||||
async send(data, callback) {
|
async send(data, callback) {
|
||||||
if (!this.connected || !this.writer) {
|
if (!this.connected || !this.writer) {
|
||||||
console.error(`${this.logHead} Failed to send data, serial port not open`);
|
console.error(`${logHead} Failed to send data, serial port not open`);
|
||||||
if (callback) {
|
if (callback) {
|
||||||
callback({ bytesSent: 0 });
|
callback({ bytesSent: 0 });
|
||||||
}
|
}
|
||||||
|
@ -350,7 +347,7 @@ class WebSerial extends EventTarget {
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error sending data:`, error);
|
console.error(`${logHead} Error sending data:`, error);
|
||||||
if (callback) {
|
if (callback) {
|
||||||
callback({ bytesSent: 0 });
|
callback({ bytesSent: 0 });
|
||||||
}
|
}
|
||||||
|
|
|
@ -196,7 +196,7 @@ class Serial extends EventTarget {
|
||||||
* @param {string|function} path - Port path or callback for virtual mode
|
* @param {string|function} path - Port path or callback for virtual mode
|
||||||
* @param {object} options - Connection options (baudRate, etc.)
|
* @param {object} options - Connection options (baudRate, etc.)
|
||||||
*/
|
*/
|
||||||
connect(path, options) {
|
async connect(path, options) {
|
||||||
if (!this._protocol) {
|
if (!this._protocol) {
|
||||||
console.error(`${this.logHead} No protocol selected, cannot connect`);
|
console.error(`${this.logHead} No protocol selected, cannot connect`);
|
||||||
return false;
|
return false;
|
||||||
|
@ -224,17 +224,14 @@ class Serial extends EventTarget {
|
||||||
|
|
||||||
// If we're connected to a different port, disconnect first
|
// If we're connected to a different port, disconnect first
|
||||||
console.log(`${this.logHead} Connected to a different port, disconnecting first`);
|
console.log(`${this.logHead} Connected to a different port, disconnecting first`);
|
||||||
this.disconnect((success) => {
|
const success = await this.disconnect();
|
||||||
if (success) {
|
if (!success) {
|
||||||
// Now connect to the new port
|
console.error(`${this.logHead} Failed to disconnect before reconnecting`);
|
||||||
console.log(`${this.logHead} Reconnecting to new port:`, path);
|
return false;
|
||||||
this._protocol.connect(path, options);
|
}
|
||||||
} else {
|
|
||||||
console.error(`${this.logHead} Failed to disconnect before reconnecting`);
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
return true;
|
console.log(`${this.logHead} Reconnecting to new port:`, path);
|
||||||
|
return this._protocol.connect(path, options);
|
||||||
}
|
}
|
||||||
|
|
||||||
console.log(`${this.logHead} Connecting to port:`, path, "with options:", options);
|
console.log(`${this.logHead} Connecting to port:`, path, "with options:", options);
|
||||||
|
@ -243,41 +240,40 @@ class Serial extends EventTarget {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Disconnect from the current connection
|
* Disconnect from the current connection
|
||||||
|
* @param {function} [callback] - Optional callback for backward compatibility
|
||||||
|
* @returns {Promise<boolean>} - Promise resolving to true if disconnection was successful
|
||||||
*/
|
*/
|
||||||
disconnect(callback) {
|
async disconnect(callback) {
|
||||||
|
// Return immediately if no protocol is selected
|
||||||
if (!this._protocol) {
|
if (!this._protocol) {
|
||||||
console.warn(`${this.logHead} No protocol selected, nothing to disconnect`);
|
console.warn(`${this.logHead} No protocol selected, nothing to disconnect`);
|
||||||
if (callback) callback(false);
|
if (callback) callback(false);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!this._protocol.connected) {
|
console.log(`${this.logHead} Disconnecting from current protocol`, this._protocol);
|
||||||
console.warn(`${this.logHead} Protocol not connected, nothing to disconnect`);
|
|
||||||
if (callback) callback(false);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
console.log(`${this.logHead} Disconnecting from current protocol`);
|
|
||||||
|
|
||||||
try {
|
try {
|
||||||
// Disconnect from the protocol
|
// Handle case where we're already disconnected
|
||||||
const result = this._protocol.disconnect((success) => {
|
if (!this._protocol.connected) {
|
||||||
if (success) {
|
console.log(`${this.logHead} Already disconnected, performing cleanup`);
|
||||||
// Ensure our connection state is updated
|
if (callback) {
|
||||||
console.log(`${this.logHead} Disconnection successful`);
|
callback(true);
|
||||||
} else {
|
|
||||||
console.error(`${this.logHead} Disconnection failed`);
|
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// Call the callback with the result
|
// Create a promise that will resolve/reject based on the protocol's disconnect result
|
||||||
if (callback) callback(success);
|
const success = await this._protocol.disconnect();
|
||||||
});
|
|
||||||
|
|
||||||
return result;
|
if (callback) callback(success);
|
||||||
|
return success;
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.error(`${this.logHead} Error during disconnect:`, error);
|
console.error(`${this.logHead} Error during disconnect:`, error);
|
||||||
if (callback) callback(false);
|
if (callback) {
|
||||||
return false;
|
callback(false);
|
||||||
|
}
|
||||||
|
return Promise.resolve(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -18,14 +18,19 @@ import { serial } from "../serial";
|
||||||
|
|
||||||
let mspHelper = null;
|
let mspHelper = null;
|
||||||
|
|
||||||
function readSerialAdapter(event) {
|
|
||||||
MSP.read(event.detail);
|
|
||||||
}
|
|
||||||
|
|
||||||
class AutoDetect {
|
class AutoDetect {
|
||||||
constructor() {
|
constructor() {
|
||||||
this.board = FC.CONFIG.boardName;
|
this.board = FC.CONFIG.boardName;
|
||||||
this.targetAvailable = false;
|
this.targetAvailable = false;
|
||||||
|
|
||||||
|
// Store bound event handlers to make removal more reliable
|
||||||
|
this.boundHandleConnect = this.handleConnect.bind(this);
|
||||||
|
this.boundHandleDisconnect = this.handleDisconnect.bind(this);
|
||||||
|
this.boundHandleSerialReceive = this.handleSerialReceive.bind(this);
|
||||||
|
}
|
||||||
|
|
||||||
|
handleSerialReceive(event) {
|
||||||
|
MSP.read(event.detail);
|
||||||
}
|
}
|
||||||
|
|
||||||
verifyBoard() {
|
verifyBoard() {
|
||||||
|
@ -51,11 +56,14 @@ class AutoDetect {
|
||||||
|
|
||||||
gui_log(i18n.getMessage("firmwareFlasherDetectBoardQuery"));
|
gui_log(i18n.getMessage("firmwareFlasherDetectBoardQuery"));
|
||||||
|
|
||||||
serial.addEventListener("connect", this.handleConnect.bind(this), { once: true });
|
|
||||||
serial.addEventListener("disconnect", this.handleDisconnect.bind(this), { once: true });
|
|
||||||
|
|
||||||
if (port.startsWith("serial")) {
|
if (port.startsWith("serial")) {
|
||||||
|
serial.addEventListener("connect", this.boundHandleConnect, { once: true });
|
||||||
|
serial.addEventListener("disconnect", this.boundHandleDisconnect, { once: true });
|
||||||
|
|
||||||
|
serial.selectProtocol("serial");
|
||||||
serial.connect(port, { baudRate: 115200 });
|
serial.connect(port, { baudRate: 115200 });
|
||||||
|
} else {
|
||||||
|
gui_log(i18n.getMessage("serialPortOpenFail"));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -73,12 +81,6 @@ class AutoDetect {
|
||||||
if (!this.targetAvailable) {
|
if (!this.targetAvailable) {
|
||||||
gui_log(i18n.getMessage("firmwareFlasherBoardVerificationFail"));
|
gui_log(i18n.getMessage("firmwareFlasherBoardVerificationFail"));
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.clearListeners();
|
|
||||||
|
|
||||||
serial.removeEventListener("receive", readSerialAdapter);
|
|
||||||
serial.removeEventListener("connect", this.handleConnect.bind(this));
|
|
||||||
serial.removeEventListener("disconnect", this.handleDisconnect.bind(this));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
onFinishClose() {
|
onFinishClose() {
|
||||||
|
@ -109,8 +111,17 @@ class AutoDetect {
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
serial.disconnect(this.onClosed.bind(this));
|
// Remove event listeners using stored references
|
||||||
|
serial.removeEventListener("receive", this.boundHandleSerialReceive);
|
||||||
|
serial.removeEventListener("connect", this.boundHandleConnect);
|
||||||
|
serial.removeEventListener("disconnect", this.boundHandleDisconnect);
|
||||||
|
|
||||||
|
// Clean up MSP listeners
|
||||||
|
MSP.clearListeners();
|
||||||
MSP.disconnect_cleanup();
|
MSP.disconnect_cleanup();
|
||||||
|
|
||||||
|
// Disconnect without passing onClosed as a callback
|
||||||
|
serial.disconnect();
|
||||||
}
|
}
|
||||||
|
|
||||||
async getBoardInfo() {
|
async getBoardInfo() {
|
||||||
|
@ -171,8 +182,8 @@ class AutoDetect {
|
||||||
|
|
||||||
onConnect(openInfo) {
|
onConnect(openInfo) {
|
||||||
if (openInfo) {
|
if (openInfo) {
|
||||||
serial.removeEventListener("receive", readSerialAdapter);
|
serial.removeEventListener("receive", this.boundHandleSerialReceive);
|
||||||
serial.addEventListener("receive", readSerialAdapter);
|
serial.addEventListener("receive", this.boundHandleSerialReceive);
|
||||||
|
|
||||||
mspHelper = new MspHelper();
|
mspHelper = new MspHelper();
|
||||||
MSP.listen(mspHelper.process_data.bind(mspHelper));
|
MSP.listen(mspHelper.process_data.bind(mspHelper));
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue