UNPKG

dynamixel

Version:

Node.js library for controlling DYNAMIXEL servo motors via U2D2 interface with Protocol 2.0 support

1,619 lines (1,393 loc) â€ĸ 141 kB
import { EventEmitter } from 'events'; import { performance } from 'perf_hooks'; // DYNAMIXEL Protocol 2.0 Constants // Packet Structure const HEADER = [0xFF, 0xFF, 0xFD, 0x00]; const BROADCAST_ID = 0xFE; // Instructions const INSTRUCTIONS = { PING: 0x01, READ: 0x02, WRITE: 0x03, REG_WRITE: 0x04, ACTION: 0x05, FACTORY_RESET: 0x06, REBOOT: 0x08, CLEAR: 0x10, CONTROL_TABLE_BACKUP: 0x20, CONTROL_TABLE_RESTORE: 0x21, STATUS: 0x55, SYNC_READ: 0x82, SYNC_WRITE: 0x83, FAST_SYNC_READ: 0x8A, BULK_READ: 0x92, BULK_WRITE: 0x93, FAST_BULK_READ: 0x9A }; // Error Flags const ERROR_FLAGS = { RESULT_FAIL: 0x01, INSTRUCTION_ERROR: 0x02, CRC_ERROR: 0x03, DATA_RANGE_ERROR: 0x04, DATA_LENGTH_ERROR: 0x05, DATA_LIMIT_ERROR: 0x06, ACCESS_ERROR: 0x07 }; // Common Control Table Addresses (varies by model) const CONTROL_TABLE = { MODEL_NUMBER: 0, MODEL_INFORMATION: 2, FIRMWARE_VERSION: 6, ID: 7, BAUD_RATE: 8, RETURN_DELAY_TIME: 9, DRIVE_MODE: 10, OPERATING_MODE: 11, SECONDARY_ID: 12, PROTOCOL_TYPE: 13, HOMING_OFFSET: 20, MOVING_THRESHOLD: 24, TEMPERATURE_LIMIT: 31, MAX_VOLTAGE_LIMIT: 32, MIN_VOLTAGE_LIMIT: 34, PWM_LIMIT: 36, VELOCITY_LIMIT: 44, MAX_POSITION_LIMIT: 48, MIN_POSITION_LIMIT: 52, EXTERNAL_PORT_MODE_1: 56, EXTERNAL_PORT_MODE_2: 57, EXTERNAL_PORT_MODE_3: 58, SHUTDOWN: 63, TORQUE_ENABLE: 64, LED: 65, STATUS_RETURN_LEVEL: 68, REGISTERED_INSTRUCTION: 69, HARDWARE_ERROR_STATUS: 70, VELOCITY_I_GAIN: 76, VELOCITY_P_GAIN: 78, POSITION_D_GAIN: 80, POSITION_I_GAIN: 82, POSITION_P_GAIN: 84, FEEDFORWARD_2ND_GAIN: 88, FEEDFORWARD_1ST_GAIN: 90, BUS_WATCHDOG: 98, GOAL_PWM: 100, GOAL_CURRENT: 102, GOAL_VELOCITY: 104, PROFILE_ACCELERATION: 108, PROFILE_VELOCITY: 112, GOAL_POSITION: 116, REALTIME_TICK: 120, MOVING: 122, MOVING_STATUS: 123, PRESENT_PWM: 124, PRESENT_LOAD: 126, PRESENT_VELOCITY: 128, PRESENT_POSITION: 132, VELOCITY_TRAJECTORY: 136, POSITION_TRAJECTORY: 140, PRESENT_INPUT_VOLTAGE: 144, PRESENT_TEMPERATURE: 146 }; // U2D2 USB Device Information const U2D2_DEVICE = { VENDOR_ID: 0x0403, // FTDI PRODUCT_ID: 0x6014, // FT232H INTERFACE: 0 }; // Indirect Address Constants const INDIRECT_ADDRESS = { BASE_ADDRESS: 168, // Starting address for indirect addresses DATA_BASE_ADDRESS: 208, // Starting address for indirect data MAX_ENTRIES: 20, // Maximum number of indirect mappings ADDRESS_SIZE: 2, // Each indirect address entry is 2 bytes DATA_SIZE: 1, // Each indirect data entry is 1 byte VALID_RANGE_MIN: 64, // Minimum valid address for indirect mapping VALID_RANGE_MAX: 227 // Maximum valid address for indirect mapping }; // Default timeouts and settings const DEFAULT_TIMEOUT = 1000; // milliseconds const DEFAULT_BAUD_RATE = 57600; const MIN_PACKET_LENGTH = 10; // Header + ID + Length + Instruction + CRC /** * DYNAMIXEL Protocol 2.0 implementation * Handles packet construction, parsing, and CRC calculation */ class Protocol2 { /** * Calculate CRC-16 for DYNAMIXEL Protocol 2.0 * Based on official ROBOTIS code: http://support.robotis.com/en/product/actuator/dynamixel_pro/communication/crc.htm * CRC-16 (IBM/ANSI) - Polynomial: x16 + x15 + x2 + 1 (0x8005), Initial Value: 0 * @param {Buffer|Array} data - Data to calculate CRC for * @returns {number} - 16-bit CRC value */ static calculateCRC(data) { const crcTable = [ 0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A, 0x804B, 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC, 0x80C9, 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5, 0x80FF, 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0, 0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1, 0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082, 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197, 0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE, 0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB, 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC, 0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145, 0x814F, 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173, 0x0176, 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162, 0x8123, 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132, 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104, 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D, 0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A, 0x832B, 0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F, 0x036A, 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356, 0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0, 0x83C5, 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1, 0x83F3, 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2, 0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7, 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E, 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A, 0x829B, 0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC, 0x82B9, 0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6, 0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0, 0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1, 0x8243, 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252, 0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264, 0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E, 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219, 0x0208, 0x820D, 0x8207, 0x0202 ]; let crcAccum = 0; const dataArray = Array.isArray(data) ? data : Array.from(data); // Official ROBOTIS algorithm: // for(j = 0; j < data_blk_size; j++) { // i = ((unsigned short)(crc_accum >> 8) ^ data_blk_ptr[j]) & 0xFF; // crc_accum = (crc_accum << 8) ^ crc_table[i]; // } for (let j = 0; j < dataArray.length; j++) { const i = ((crcAccum >> 8) ^ dataArray[j]) & 0xFF; crcAccum = (crcAccum << 8) ^ crcTable[i]; } // Ensure 16-bit result crcAccum = crcAccum & 0xFFFF; return crcAccum; } /** * Create an instruction packet * @param {number} id - DYNAMIXEL ID (0-252, 0xFE for broadcast) * @param {number} instruction - Instruction byte * @param {Array|Buffer} parameters - Parameter data * @returns {Buffer} - Complete instruction packet */ static createInstructionPacket(id, instruction, parameters = []) { const paramArray = Array.isArray(parameters) ? parameters : Array.from(parameters); const length = 3 + paramArray.length; // Instruction + Parameters + CRC(2) // Build packet without CRC const packet = [ ...HEADER, // Header: 0xFF 0xFF 0xFD 0x00 id, // Packet ID length & 0xFF, // Length low byte (length >> 8) & 0xFF, // Length high byte instruction, // Instruction ...paramArray // Parameters ]; // Calculate CRC for the entire packet (excluding only the CRC bytes) // According to ROBOTIS documentation: CRC is calculated on the full packet const crc = this.calculateCRC(packet); // Add CRC to packet packet.push(crc & 0xFF); // CRC low byte packet.push((crc >> 8) & 0xFF); // CRC high byte return Buffer.from(packet); } /** * Parse a status packet * @param {Buffer} buffer - Raw packet data * @returns {Object|null} - Parsed packet or null if invalid */ static parseStatusPacket(buffer) { if (!buffer || buffer.length < MIN_PACKET_LENGTH) { return null; } // Check header if (buffer[0] !== HEADER[0] || buffer[1] !== HEADER[1] || buffer[2] !== HEADER[2] || buffer[3] !== HEADER[3]) { return null; } const id = buffer[4]; const length = buffer[5] | (buffer[6] << 8); const instruction = buffer[7]; const error = buffer[8]; // Check if we have enough data for the complete packet if (buffer.length < 9 + length - 2) { return null; } // Extract parameters (everything between error and CRC) const paramLength = length - 4; // length - instruction - error - CRC(2) const parameters = Array.from(buffer.slice(9, 9 + paramLength)); // Extract CRC const crcReceived = buffer[9 + paramLength] | (buffer[9 + paramLength + 1] << 8); // Verify CRC - calculate on entire packet excluding only the CRC bytes const crcData = Array.from(buffer.slice(0, 9 + paramLength)); const crcCalculated = this.calculateCRC(crcData); if (crcReceived !== crcCalculated) { throw new Error(`CRC mismatch: received ${crcReceived.toString(16)}, calculated ${crcCalculated.toString(16)}`); } return { id, instruction, error, parameters, length, raw: buffer }; } /** * Create a PING instruction packet * @param {number} id - DYNAMIXEL ID (0-252, 0xFE for broadcast) * @returns {Buffer} - PING instruction packet */ static createPingPacket(id) { return this.createInstructionPacket(id, INSTRUCTIONS.PING, []); } /** * Parse PING status packet to extract device information * @param {Object} statusPacket - Parsed status packet * @returns {Object|null} - Device information or null if not a PING response */ static parsePingResponse(statusPacket) { if (!statusPacket || statusPacket.instruction !== INSTRUCTIONS.STATUS) { return null; } if (statusPacket.parameters.length < 3) { return null; } const modelNumber = statusPacket.parameters[0] | (statusPacket.parameters[1] << 8); const firmwareVersion = statusPacket.parameters[2]; return { id: statusPacket.id, modelNumber, firmwareVersion, error: statusPacket.error }; } /** * Check if buffer contains a complete packet * @param {Buffer} buffer - Buffer to check * @returns {number} - Length of complete packet, or 0 if incomplete */ static getCompletePacketLength(buffer) { if (!buffer || buffer.length < 7) { return 0; } // Check for header if (buffer[0] !== HEADER[0] || buffer[1] !== HEADER[1] || buffer[2] !== HEADER[2] || buffer[3] !== HEADER[3]) { return 0; } const length = buffer[5] | (buffer[6] << 8); const totalLength = 7 + length; // Header(4) + ID(1) + Length(2) + Data(length) return buffer.length >= totalLength ? totalLength : 0; } /** * Convert error code to human-readable string * @param {number} errorCode - Error code from status packet * @returns {string} - Error description */ static getErrorDescription(errorCode) { const errors = []; if (errorCode & ERROR_FLAGS.RESULT_FAIL) errors.push('Result Fail'); if (errorCode & ERROR_FLAGS.INSTRUCTION_ERROR) errors.push('Instruction Error'); if (errorCode & ERROR_FLAGS.CRC_ERROR) errors.push('CRC Error'); if (errorCode & ERROR_FLAGS.DATA_RANGE_ERROR) errors.push('Data Range Error'); if (errorCode & ERROR_FLAGS.DATA_LENGTH_ERROR) errors.push('Data Length Error'); if (errorCode & ERROR_FLAGS.DATA_LIMIT_ERROR) errors.push('Data Limit Error'); if (errorCode & ERROR_FLAGS.ACCESS_ERROR) errors.push('Access Error'); return errors.length > 0 ? errors.join(', ') : 'No Error'; } } // Dynamic import for USB module let usb; try { const usbModule = await import('usb'); usb = usbModule.usb; } catch (_error) { // USB module not available usb = null; } /** * U2D2 USB to TTL connection handler (ES Module version) * Manages USB communication with DYNAMIXEL devices through U2D2 */ class U2D2Connection extends EventEmitter { constructor(options = {}) { super(); this.device = null; this.interface = null; this.endpoint = null; this.timeout = options.timeout || DEFAULT_TIMEOUT; this.isConnected = false; this.receiveBuffer = Buffer.alloc(0); // Enable debug mode if (options.debug && usb) { usb.setDebugLevel(4); } } /** * Find and connect to U2D2 device * @returns {Promise<boolean>} - Success status */ async connect() { try { if (!usb) { throw new Error('USB module not available. Install with: npm install usb'); } console.log('🔍 Starting U2D2 connection process...'); // Find U2D2 device const devices = usb.getDeviceList(); console.log(`📋 Scanning ${devices.length} USB devices for U2D2...`); this.device = devices.find(device => device.deviceDescriptor.idVendor === U2D2_DEVICE.VENDOR_ID && device.deviceDescriptor.idProduct === U2D2_DEVICE.PRODUCT_ID ); if (!this.device) { throw new Error('U2D2 device not found. Please check connection.'); } console.log(`✅ Found U2D2 device (VID: 0x${this.device.deviceDescriptor.idVendor.toString(16).padStart(4, '0')}, PID: 0x${this.device.deviceDescriptor.idProduct.toString(16).padStart(4, '0')})`); // Try to get device info for debugging try { const deviceInfo = { busNumber: this.device.busNumber, deviceAddress: this.device.deviceAddress, portNumbers: this.device.portNumbers, deviceDescriptor: { bcdDevice: this.device.deviceDescriptor.bcdDevice, bDeviceClass: this.device.deviceDescriptor.bDeviceClass, bDeviceSubClass: this.device.deviceDescriptor.bDeviceSubClass, bDeviceProtocol: this.device.deviceDescriptor.bDeviceProtocol, bMaxPacketSize0: this.device.deviceDescriptor.bMaxPacketSize0, bNumConfigurations: this.device.deviceDescriptor.bNumConfigurations } }; console.log('📊 Device Info:', JSON.stringify(deviceInfo, null, 2)); } catch (infoError) { console.log('âš ī¸ Could not get detailed device info:', infoError.message); } // Open device console.log('🔐 Opening USB device...'); try { this.device.open(); console.log('✅ USB device opened successfully'); } catch (openError) { console.error('❌ Failed to open USB device:', openError.message); // Provide specific error messages for common issues if (openError.message.includes('LIBUSB_ERROR_ACCESS')) { throw new Error(`USB Access Error: Permission denied. This usually means: - On macOS: You may need to run with sudo, or add your user to the 'wheel' group - The device might be in use by another application - System security settings may be blocking access - Try running: sudo node examples/device-discovery.js - Or check if any other software is using the U2D2 device`); } else if (openError.message.includes('LIBUSB_ERROR_BUSY')) { throw new Error('USB Busy Error: The U2D2 device is already in use by another application. Please close any other software using the device.'); } else if (openError.message.includes('LIBUSB_ERROR_NO_DEVICE')) { throw new Error('USB No Device Error: The U2D2 device was disconnected during connection attempt.'); } else { throw new Error(`USB Error: ${openError.message}`); } } // Get interface console.log(`🔌 Getting USB interface ${U2D2_DEVICE.INTERFACE}...`); try { this.interface = this.device.interface(U2D2_DEVICE.INTERFACE); console.log('✅ USB interface obtained'); } catch (interfaceError) { throw new Error(`Failed to get USB interface: ${interfaceError.message}`); } // Check if kernel driver is active and handle it console.log('🔍 Checking kernel driver status...'); try { const isKernelDriverActive = this.interface.isKernelDriverActive(); console.log(`📋 Kernel driver active: ${isKernelDriverActive}`); if (isKernelDriverActive) { console.log('🔧 Detaching kernel driver...'); this.interface.detachKernelDriver(); console.log('✅ Kernel driver detached'); } console.log('🔒 Claiming USB interface...'); this.interface.claim(); console.log('✅ USB interface claimed'); } catch (claimError) { console.error('❌ Failed to claim interface:', claimError.message); if (claimError.message.includes('LIBUSB_ERROR_BUSY')) { throw new Error('Interface Busy Error: The USB interface is already claimed by another process. Please close any other software using the U2D2.'); } else if (claimError.message.includes('LIBUSB_ERROR_ACCESS')) { throw new Error('Interface Access Error: Permission denied when claiming interface. Try running with sudo.'); } else { throw new Error(`Failed to claim USB interface: ${claimError.message}`); } } // Find bulk endpoints console.log('🔍 Looking for USB endpoints...'); const endpoints = this.interface.endpoints; console.log(`📋 Found ${endpoints.length} endpoints`); endpoints.forEach((ep, index) => { console.log(` Endpoint ${index}: direction=${ep.direction}, type=${ep.transferType}, address=0x${ep.address.toString(16)}`); }); // Find bulk endpoints - handle both string 'bulk' and numeric 2 (USB_ENDPOINT_XFER_BULK) this.inEndpoint = endpoints.find(ep => ep.direction === 'in' && (ep.transferType === 'bulk' || ep.transferType === 2) ); this.outEndpoint = endpoints.find(ep => ep.direction === 'out' && (ep.transferType === 'bulk' || ep.transferType === 2) ); if (!this.inEndpoint || !this.outEndpoint) { console.log('❌ Endpoint detection details:'); endpoints.forEach((ep, index) => { console.log(` Endpoint ${index}: direction=${ep.direction}, transferType=${ep.transferType} (${typeof ep.transferType}), address=0x${ep.address.toString(16)}`); }); throw new Error('Could not find bulk endpoints on U2D2 device'); } console.log(`✅ Found bulk endpoints - IN: 0x${this.inEndpoint.address.toString(16)}, OUT: 0x${this.outEndpoint.address.toString(16)}`); // Start listening for incoming data console.log('📡 Starting data reception...'); this.startReceiving(); console.log('✅ Data reception started'); this.isConnected = true; this.emit('connected'); console.log('🎉 U2D2 connection established successfully!'); return true; } catch (error) { console.error('đŸ’Ĩ U2D2 connection failed:', error.message); this.emit('error', error); return false; } } /** * Disconnect from U2D2 device */ async disconnect() { try { if (this.inEndpoint) { this.inEndpoint.stopPoll(); } if (this.interface) { this.interface.release(() => { if (this.device) { this.device.close(); } }); } this.isConnected = false; this.emit('disconnected'); console.log('✅ U2D2 disconnected successfully'); } catch (error) { console.error('❌ Error during U2D2 disconnect:', error.message); this.emit('error', error); } } /** * Start receiving data from the device */ startReceiving() { if (!this.inEndpoint) return; this.inEndpoint.on('data', (data) => { this.receiveBuffer = Buffer.concat([this.receiveBuffer, data]); this.processReceiveBuffer(); }); this.inEndpoint.on('error', (error) => { console.error('❌ USB receive error:', error.message); this.emit('error', error); }); this.inEndpoint.startPoll(1, 64); } /** * Process received data buffer */ processReceiveBuffer() { // Prevent buffer from growing too large (max 1KB) if (this.receiveBuffer.length > 1024) { console.warn('âš ī¸ Receive buffer too large, clearing'); this.receiveBuffer = Buffer.alloc(0); return; } let processedPackets = 0; const maxPacketsPerCall = 10; // Prevent infinite loops while (this.receiveBuffer.length >= 10 && processedPackets < maxPacketsPerCall) { const packetLength = Protocol2.getCompletePacketLength(this.receiveBuffer); if (packetLength === 0) { // Invalid or incomplete packet, remove one byte and try again this.receiveBuffer = this.receiveBuffer.slice(1); continue; } if (this.receiveBuffer.length < packetLength) { // Not enough data for complete packet yet break; } const packet = this.receiveBuffer.slice(0, packetLength); this.receiveBuffer = this.receiveBuffer.slice(packetLength); this.emit('packet', packet); processedPackets++; } } /** * Send data to the device * @param {Buffer|Array} data - Data to send */ async send(data) { return new Promise((resolve, reject) => { if (!this.isConnected || !this.outEndpoint) { reject(new Error('U2D2 not connected')); return; } const buffer = Buffer.isBuffer(data) ? data : Buffer.from(data); this.outEndpoint.transfer(buffer, (error) => { if (error) { reject(new Error(`USB send error: ${error.message}`)); } else { resolve(); } }); }); } /** * Send packet and wait for response * @param {Buffer} packet - Packet to send * @param {number} expectedId - Expected device ID in response * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Buffer>} - Response packet */ async sendAndWaitForResponse(packet, expectedId = null, timeout = null) { return new Promise((resolve, reject) => { const timeoutMs = timeout || this.timeout; const onPacket = (statusPacket) => { if (expectedId === null || statusPacket[4] === expectedId) { clearTimeout(timeoutId); this.removeListener('packet', onPacket); resolve(statusPacket); } }; this.on('packet', onPacket); const timeoutId = setTimeout(() => { this.removeListener('packet', onPacket); reject(new Error(`Timeout waiting for response from device ${expectedId || 'any'}`)); }, timeoutMs); this.send(packet).catch(reject); }); } /** * Ping a device * @param {number} id - Device ID * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Object>} - Ping response */ async ping(id, timeout = null) { const packet = Protocol2.createPingPacket(id); const response = await this.sendAndWaitForResponse(packet, id, timeout); // First parse the raw buffer into a status packet const statusPacket = Protocol2.parseStatusPacket(response); if (!statusPacket) { throw new Error(`Invalid response from device ${id}`); } // Then extract ping response information return Protocol2.parsePingResponse(statusPacket); } /** * @typedef {Object} DeviceInfo * @property {number} id - Device ID * @property {number} modelNumber - Device model number * @property {string} modelName - Device model name * @property {number} firmwareVersion - Firmware version */ /** * Discover devices on the bus * @param {Object} options - Discovery options * @returns {Promise<DeviceInfo[]>} - Array of discovered devices */ async discoverDevices(options = {}) { const { range = 'quick', timeout = 100, onProgress } = options; const devices = []; const startId = range === 'quick' ? 1 : 1; const endId = range === 'quick' ? 20 : 252; for (let id = startId; id <= endId; id++) { try { const response = await this.ping(id, timeout); devices.push({ id, ...response }); if (onProgress) { onProgress({ id, found: true, total: endId - startId + 1, current: id - startId + 1 }); } } catch (_error) { if (onProgress) { onProgress({ id, found: false, total: endId - startId + 1, current: id - startId + 1 }); } } } return devices; } /** * Set baud rate (placeholder - U2D2 handles this automatically) * @param {number} baudRate - Baud rate */ setBaudRate(baudRate) { console.log(`â„šī¸ U2D2 baud rate set to ${baudRate} (handled automatically by U2D2)`); } /** * Get current baud rate * @returns {number} - Current baud rate */ getBaudRate() { return 57600; // U2D2 default } /** * Get connection status * @returns {boolean} - Connection status */ getConnectionStatus() { return this.isConnected; } /** * @typedef {Object} USBDeviceInfo * @property {number} vendorId - USB vendor ID * @property {number} productId - USB product ID * @property {number} busNumber - USB bus number * @property {number} deviceAddress - Device address on bus * @property {boolean} isU2D2 - Whether this is a U2D2 device */ /** * @typedef {Object} SystemInfo * @property {string} platform - Operating system platform * @property {string} arch - System architecture * @property {string} nodeVersion - Node.js version * @property {boolean} usbAvailable - Whether USB module is available * @property {string} usbVersion - USB module version info */ /** * @typedef {Object} USBDiagnostics * @property {boolean} usbModuleAvailable - Whether USB module is available * @property {USBDeviceInfo[]} u2d2Devices - Found U2D2 devices * @property {USBDeviceInfo[]} allDevices - All USB devices * @property {string[]} errors - Array of error messages * @property {number} totalDevices - Total number of USB devices * @property {SystemInfo} systemInfo - System information */ /** * List available USB devices * @returns {USBDeviceInfo[]} - Array of USB devices */ static listUSBDevices() { if (!usb) { console.warn('âš ī¸ USB module not available'); return []; } const devices = usb.getDeviceList(); return devices.map(device => ({ vendorId: device.deviceDescriptor.idVendor, productId: device.deviceDescriptor.idProduct, busNumber: device.busNumber, deviceAddress: device.deviceAddress, isU2D2: device.deviceDescriptor.idVendor === U2D2_DEVICE.VENDOR_ID && device.deviceDescriptor.idProduct === U2D2_DEVICE.PRODUCT_ID })); } /** * Get system information * @returns {SystemInfo} - System information */ static getSystemInfo() { return { platform: process.platform, arch: process.arch, nodeVersion: process.version, usbAvailable: usb !== null, usbVersion: usb ? 'Available' : 'Not available' }; } /** * Perform USB diagnostics * @returns {USBDiagnostics} - Diagnostic results */ static performUSBDiagnostics() { const results = { usbModuleAvailable: usb !== null, u2d2Devices: [], allDevices: [], errors: [], totalDevices: 0, systemInfo: this.getSystemInfo() }; if (!usb) { results.errors.push('USB module not available. Install with: npm install usb'); return results; } try { const devices = usb.getDeviceList(); results.allDevices = devices.map(device => ({ vendorId: device.deviceDescriptor.idVendor, productId: device.deviceDescriptor.idProduct, busNumber: device.busNumber, deviceAddress: device.deviceAddress })); results.totalDevices = results.allDevices.length; results.u2d2Devices = results.allDevices.filter(device => device.vendorId === U2D2_DEVICE.VENDOR_ID && device.productId === U2D2_DEVICE.PRODUCT_ID ); } catch (error) { results.errors.push(`Failed to get device list: ${error.message}`); } return results; } } // Dynamic imports for SerialPort let SerialPort, SerialPortList; try { const serialportModule = await import('serialport'); SerialPort = serialportModule.SerialPort; // Try to get list function (different export in different versions) if (serialportModule.list) { SerialPortList = serialportModule.list; } else if (serialportModule.SerialPort.list) { SerialPortList = serialportModule.SerialPort.list; } else { // Fallback - try dynamic import try { const { list } = await import('@serialport/bindings-cpp'); SerialPortList = list; } catch (_listError) { console.warn('âš ī¸ Could not import SerialPort list function'); } } } catch (_error) { // SerialPort module not available SerialPort = null; SerialPortList = null; } /** * Node.js SerialPort Connection Handler (ES Module version) * For use in Node.js environments and Electron main process */ class SerialConnection extends EventEmitter { constructor(options = {}) { super(); this.port = null; this.timeout = options.timeout || DEFAULT_TIMEOUT; this.baudRate = options.baudRate || 57600; this.highWaterMark = options.highWaterMark !== undefined ? options.highWaterMark : 65536; // Default 64KB this.isConnected = false; this.receiveBuffer = Buffer.alloc(0); this.portPath = options.portPath || null; } /** * Find and connect to U2D2 device via serial port * @param {string} portPath - Optional specific port path * @returns {Promise<boolean>} - Success status */ async connect(portPath = null) { try { if (!SerialPort) { throw new Error('SerialPort module not available. Install with: npm install serialport'); } console.log('🔍 Starting serial connection process...'); // Use provided port path or try to find U2D2 const targetPort = portPath || this.portPath || await this.findU2D2Port(); if (!targetPort) { throw new Error('No U2D2 device found. Please specify port path or ensure device is connected.'); } console.log(`📡 Connecting to serial port: ${targetPort}`); // Create SerialPort instance this.port = new SerialPort({ path: targetPort, baudRate: this.baudRate, dataBits: 8, stopBits: 1, parity: 'none', flowControl: false, autoOpen: false, highWaterMark: this.highWaterMark }); // Open the port await new Promise((resolve, reject) => { this.port.open((error) => { if (error) { reject(new Error(`Failed to open serial port: ${error.message}`)); } else { resolve(); } }); }); console.log('✅ Serial port opened successfully'); // Set up data reception this.port.on('data', (data) => { this.receiveBuffer = Buffer.concat([this.receiveBuffer, data]); this.processReceiveBuffer(); }); this.port.on('error', (error) => { console.error('❌ Serial port error:', error.message); this.emit('error', error); }); this.port.on('close', () => { console.log('📡 Serial port closed'); this.isConnected = false; this.emit('disconnected'); }); this.isConnected = true; this.emit('connected'); return true; } catch (error) { console.error('❌ Serial connection failed:', error.message); this.emit('error', error); return false; } } /** * Find U2D2 device port automatically * @returns {Promise<string|null>} - Port path or null if not found */ async findU2D2Port() { if (!SerialPortList) { console.log('â„šī¸ Port listing not available, manual port specification required'); return null; } try { console.log('🔍 Scanning for U2D2 device...'); const ports = await SerialPortList(); console.log(`📋 Found ${ports.length} serial ports:`); ports.forEach((port, index) => { console.log(` ${index + 1}. ${port.path} - ${port.manufacturer || 'Unknown'} (VID: ${port.vendorId || 'N/A'}, PID: ${port.productId || 'N/A'})`); }); // Look for FTDI devices (U2D2 uses FTDI chip) const ftdiPorts = ports.filter(port => { const vid = port.vendorId?.toLowerCase(); const manufacturer = port.manufacturer?.toLowerCase(); return vid === '0403' || // FTDI Vendor ID manufacturer?.includes('ftdi') || manufacturer?.includes('future technology') || port.serialNumber?.includes('u2d2'); }); if (ftdiPorts.length === 0) { console.log('❌ No FTDI/U2D2 devices found'); return null; } if (ftdiPorts.length === 1) { const selectedPort = ftdiPorts[0]; console.log(`✅ Found U2D2 device: ${selectedPort.path} (${selectedPort.manufacturer})`); return selectedPort.path; } // Multiple FTDI devices found - try to pick the best one console.log(`📋 Found ${ftdiPorts.length} FTDI devices:`); ftdiPorts.forEach((port, index) => { console.log(` ${index + 1}. ${port.path} - ${port.manufacturer} (PID: ${port.productId})`); }); // Prefer FT232H (U2D2's chip) with PID 6014 const u2d2Port = ftdiPorts.find(port => port.productId?.toLowerCase() === '6014'); if (u2d2Port) { console.log(`✅ Found U2D2 device: ${u2d2Port.path}`); return u2d2Port.path; } // Fallback to first FTDI device const fallbackPort = ftdiPorts[0]; console.log(`âš ī¸ Using first FTDI device: ${fallbackPort.path}`); return fallbackPort.path; } catch (error) { console.error('❌ Error scanning ports:', error.message); return null; } } /** * Disconnect from serial port */ async disconnect() { try { if (this.port && this.port.isOpen) { await new Promise((resolve) => { this.port.close(() => { resolve(); }); }); } this.isConnected = false; this.emit('disconnected'); console.log('✅ Serial port disconnected'); } catch (error) { console.error('❌ Error during serial disconnect:', error.message); this.emit('error', error); } } /** * Process received data buffer */ processReceiveBuffer() { while (this.receiveBuffer.length >= 10) { const packetLength = Protocol2.getCompletePacketLength(this.receiveBuffer); if (packetLength === 0) { // Invalid or incomplete packet, remove one byte and try again this.receiveBuffer = this.receiveBuffer.slice(1); continue; } if (this.receiveBuffer.length < packetLength) { // Not enough data for complete packet yet break; } const packet = this.receiveBuffer.slice(0, packetLength); this.receiveBuffer = this.receiveBuffer.slice(packetLength); this.emit('packet', packet); } } /** * Send data to the device * @param {Buffer|Array} data - Data to send */ async send(data) { return new Promise((resolve, reject) => { if (!this.isConnected || !this.port) { reject(new Error('Serial port not connected')); return; } const buffer = Buffer.isBuffer(data) ? data : Buffer.from(data); this.port.write(buffer, (error) => { if (error) { reject(new Error(`Serial send error: ${error.message}`)); } else { resolve(); } }); }); } /** * Send packet and wait for response * @param {Buffer} packet - Packet to send * @param {number} expectedId - Expected device ID in response * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Buffer>} - Response packet */ async sendAndWaitForResponse(packet, expectedId = null, timeout = null) { return new Promise((resolve, reject) => { const timeoutMs = timeout || this.timeout; const onPacket = (statusPacket) => { if (expectedId === null || statusPacket[4] === expectedId) { clearTimeout(timeoutId); this.removeListener('packet', onPacket); resolve(statusPacket); } }; this.on('packet', onPacket); const timeoutId = setTimeout(() => { this.removeListener('packet', onPacket); reject(new Error(`Timeout waiting for response from device ${expectedId || 'any'}`)); }, timeoutMs); this.send(packet).catch(reject); }); } /** * Ping a device * @param {number} id - Device ID * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Object>} - Ping response */ async ping(id, timeout = null) { const packet = Protocol2.createPingPacket(id); const response = await this.sendAndWaitForResponse(packet, id, timeout); // First parse the raw buffer into a status packet const statusPacket = Protocol2.parseStatusPacket(response); if (!statusPacket) { throw new Error(`Invalid response from device ${id}`); } // Then extract ping response information return Protocol2.parsePingResponse(statusPacket); } /** * @typedef {Object} DeviceInfo * @property {number} id - Device ID * @property {number} modelNumber - Device model number * @property {string} modelName - Device model name * @property {number} firmwareVersion - Firmware version */ /** * Discover devices on the bus * @param {Object} options - Discovery options * @returns {Promise<DeviceInfo[]>} - Array of discovered devices */ async discoverDevices(options = {}) { const { range = 'quick', timeout = 100, onProgress } = options; const devices = []; const startId = range === 'quick' ? 1 : 1; const endId = range === 'quick' ? 20 : 252; for (let id = startId; id <= endId; id++) { try { const response = await this.ping(id, timeout); devices.push({ id, ...response }); if (onProgress) { onProgress({ id, found: true, total: endId - startId + 1, current: id - startId + 1 }); } } catch (_error) { if (onProgress) { onProgress({ id, found: false, total: endId - startId + 1, current: id - startId + 1 }); } } } return devices; } /** * Set baud rate * @param {number} baudRate - Baud rate */ setBaudRate(baudRate) { this.baudRate = baudRate; if (this.port && this.port.isOpen) { this.port.update({ baudRate }, (error) => { if (error) { console.error('❌ Failed to update baud rate:', error.message); } else { console.log(`✅ Baud rate updated to ${baudRate}`); } }); } } /** * Get current baud rate * @returns {number} - Current baud rate */ getBaudRate() { return this.baudRate; } /** * Get connection status * @returns {Object} - Connection status */ getConnectionStatus() { return { connected: this.isConnected, type: 'serial', port: this.port ? this.port.path : null, baudRate: this.baudRate, highWaterMark: this.highWaterMark }; } /** * @typedef {Object} SerialPortInfo * @property {string} path - Port path * @property {string} [manufacturer] - Manufacturer name * @property {string} [vendorId] - Vendor ID * @property {string} [productId] - Product ID * @property {string} [serialNumber] - Serial number * @property {boolean} isU2D2 - Whether this is a U2D2 device */ /** * List available serial ports * @returns {Promise<SerialPortInfo[]>} - Array of available ports */ static async listSerialPorts() { if (!SerialPortList) { return []; } try { const ports = await SerialPortList(); return ports.map(port => ({ path: port.path, manufacturer: port.manufacturer, vendorId: port.vendorId, productId: port.productId, serialNumber: port.serialNumber, isU2D2: port.vendorId?.toLowerCase() === '0403' && port.productId?.toLowerCase() === '6014' })); } catch (error) { console.error('❌ Error listing serial ports:', error.message); return []; } } /** * Check if SerialPort is available * @returns {boolean} - True if available */ static isAvailable() { return SerialPort !== null; } /** * Get SerialPort module information * @returns {Object} - Module information */ static getModuleInfo() { return { available: SerialPort !== null, listAvailable: SerialPortList !== null, version: SerialPort ? 'Available' : 'Not available' }; } } /** * Web Serial API Connection Handler * For use in Electron renderer processes and modern browsers */ class WebSerialConnection extends EventEmitter { constructor(options = {}) { super(); this.port = null; this.reader = null; this.writer = null; this.timeout = options.timeout || DEFAULT_TIMEOUT; this.baudRate = options.baudRate || 57600; this.isConnected = false; this.receiveBuffer = new Uint8Array(0); this.readPromise = null; // Check if Web Serial API is available if (typeof navigator === 'undefined' || !navigator.serial) { throw new Error('Web Serial API not available. This requires Chrome/Chromium-based browsers or Electron with Web Serial support.'); } } /** * Request and connect to a serial port using Web Serial API * @param {Object} filters - Optional filters for port selection * @returns {Promise<boolean>} - Success status */ async connect(filters = null) { try { console.log('🔍 Requesting serial port access...'); // Default filters for U2D2 device (FTDI-based) const defaultFilters = [ { usbVendorId: 0x0403, usbProductId: 0x6014 }, // FTDI FT232H (U2D2) { usbVendorId: 0x0403, usbProductId: 0x6001 }, // FTDI FT232R { usbVendorId: 0x0403 } // Any FTDI device ]; const requestFilters = filters || defaultFilters; // Request port with user interaction this.port = await navigator.serial.requestPort({ filters: requestFilters }); if (!this.port) { throw new Error('No serial port selected'); } console.log('✅ Serial port selected'); // Get port info for debugging const portInfo = this.port.getInfo(); console.log('📊 Port Info:', portInfo); // Open the port console.log(`🔌 Opening serial port at ${this.baudRate} baud...`); await this.port.open({ baudRate: this.baudRate, dataBits: 8, stopBits: 1, parity: 'none', flowControl: 'none' }); console.log('✅ Serial port opened successfully'); // Get reader and writer this.reader = this.port.readable.getReader(); this.writer = this.port.writable.getWriter(); // Start reading data this.startReceiving(); this.isConnected = true; this.emit('connected'); return true; } catch (error) { console.error('❌ Web Serial connection failed:', error.message); if (error.name === 'NotFoundError') { throw new Error('No compatible serial device found or user cancelled selection'); } else if (error.name === 'SecurityError') { throw new Error('Serial port access denied. Enable Web Serial API in browser settings'); } else if (error.name === 'NetworkError') { throw new Error('Serial port is already open in another tab or application'); } this.emit('error', error); return false; } } /** * Connect to a previously authorized port (if available) * @returns {Promise<boolean>} - Success status */ async connectToPreviousPort() { try { console.log('🔍 Looking for previously authorized ports...'); const ports = await navigator.serial.getPorts(); if (ports.length === 0) { throw new Error('No previously authorized ports found'); } console.log(`📋 Found ${ports.length} previously authorized port(s)`); // Use the first available port this.port = ports[0]; const portInfo = this.port.getInfo(); console.log('📊 Using port:', portInfo); // Open the port await this.port.open({ baudRate: this.baudRate, dataBits: 8, stopBits: 1, parity: 'none', flowControl: 'none' }); // Get reader and writer this.reader = this.port.readable.getReader(); this.writer = this.port.writable.getWriter(); // Start reading data this.startReceiving(); this.isConnected = true; this.emit('connected'); return true; } catch (error) { console.error('❌ Failed to connect to previous port:', error.message); this.emit('error', error); return false; } } /** * Disconnect from the serial port */ async disconnect() { try { this.isConnected = false; // Stop reading if (this.reader) { await this.reader.cancel(); this.reader.releaseLock(); this.reader = null; } // Release writer if (this.writer) { this.writer.releaseLock(); this.writer = null; } // Close port if (this.port) { await this.port.close(); this.port = null; } this.emit('disconnected'); } catch (error) { console.error('❌ Error during disconnect:', error.message); this.emit('error', error); } } /** * Start receiving data from the serial port */ async startReceiving() { if (!this.reader) return; try { this.readPromise = this.readLoop(); await this.readPromise; } catch (error) { if (error.name !== 'AbortError') { console.error('❌ Error in receive loop:', error.message); this.emit('error', error); } } } /** * Main read loop for processing incoming data */ async readLoop() { while (this.isConnected && this.reader) { try { const { value, done } = await this.reader.read(); if (done) { console.log('📡 Serial port reading completed'); break; } if (value) { // Concatenate new data with existing buffer const newBuffer = new Uint8Array(this.receiveBuffer.length + value.length); newBuffer.set(this.receiveBuffer); newBuffer.set(value, this.receiveBuffer.length); this.receiveBuffer = newBuffer; this.processReceiveBuffer(); } } catch (error) { if (error.name === 'AbortError') { console.log('📡 Serial reading cancelled'); break; } throw error; } } } /** * Process received data buffer for complete packets */ processReceiveBuffer() { while (this.receiveBuffer.length > 0) { // Convert to Buffer for Protocol2 compatibility const bufferForCheck = Buffer.from(this.receiveBuffer); const packetLength = Protocol2.getCompletePacketLength(bufferForCheck); if (packetLength === 0) { // No complete packet yet, wait for more data break; } // Extract complete packet const packetData = Buffer.from(this.receiveBuffer.slice(0, packetLength)); this.receiveBuffer = this.receiveBuffer.slice(packetLength); // Parse and emit packet try { const packet = Protocol2.parseStatusPacket(packetData); if (packet) { this.emit('packet', packet); } } catch (error) { console.error('❌ Packet parsing error:', error.message); this.emit('error', error); } } } /** * Send data to the serial port * @param {Buffer|Uint8Array} data - Data to send * @returns {Promise<boolean>} - Success status */ async send(data) { if (!this.isConnected || !this.writer) { throw new Error('Serial port not connected'); } try { // Convert Buffer to Uint8Array if needed const dataToSend = data instanceof Buffer ? new Uint8Array(data) : data; await this.writer.write(dataToSend); return true; } catch (error) { throw new Error(`Failed to send data: ${error.message}`); } } /** * Send instruction packet and wait for response * @param {Buffer} packet - Instruction packet to send * @param {number} expectedId - Expected response ID (null for any) * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Object>} - Parsed status packet */ async sendAndWaitForResponse(packet, expectedId = null, timeout = null) { const actualTimeout = timeout || this.timeout; return new Promise((resolve, reject) => { const timeoutHandle = setTimeout(() => { this.removeAllListeners('packet'); reject(new Error(`Timeout waiting for response from ID ${expectedId}`)); }, actualTimeout); const onPacket = (statusPacket) => { if (expectedId === null || statusPacket.id === expectedId) { clearTimeout(timeoutHandle); this.removeListener('packet', onPacket); resolve(statusPacket); } }; this.on('packet', onPacket); this.send(packet).catch((error) => { clearTimeout(timeoutHandle); this.removeListener('packet', onPacket); reject(error); }); }); } /** * Ping a specific DYNAMIXEL device * @param {number} id - DYNAMIXEL ID * @param {number} timeout - Timeout in milliseconds * @returns {Promise<Object>} - Device information */ async ping(id, timeout = null) { const packet = Protocol2.createPingPacket(id); const response = await this.sendAndWaitForResponse(packet, id, timeout); const deviceInfo = Protocol2.parsePingResponse(response); if (!deviceInfo) { throw new Error(`Invalid ping response from ID ${id}`); } return deviceInfo; } /** * @typedef {Object} DeviceInfo * @property