diff --git a/ClientLib/build.gradle b/ClientLib/build.gradle index 8c5d1e120f..ecc8ef7827 100644 --- a/ClientLib/build.gradle +++ b/ClientLib/build.gradle @@ -111,7 +111,6 @@ dependencies { //MP4 generation library compile 'com.googlecode.mp4parser:isoparser:1.1.7' - compile 'org.droidplanner.android:usb-serial-android:0.1.0' debugCompile project(':Mavlink') // sitlCompile project(':Mavlink') diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/BuildInfo.java b/ClientLib/src/main/java/com/hoho/android/usbserial/BuildInfo.java new file mode 100644 index 0000000000..1f0d363650 --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/BuildInfo.java @@ -0,0 +1,19 @@ +package com.hoho.android.usbserial; + +/** + * Static container of information about this library. + */ +public final class BuildInfo { + + /** + * The current version of this library. Values are of the form + * "major.minor.micro[-suffix]". A suffix of "-pre" indicates a pre-release + * of the version preceeding it. + */ + public static final String VERSION = "0.2.0-pre"; + + private BuildInfo() { + throw new IllegalStateException("Non-instantiable class."); + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java new file mode 100644 index 0000000000..321e3a288e --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CdcAcmSerialDriver.java @@ -0,0 +1,336 @@ +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbConstants; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbInterface; +import android.os.Build; +import android.util.Log; +import android.util.SparseArray; + +import java.io.IOException; +import java.util.LinkedHashMap; +import java.util.Map; + +/** + * USB CDC/ACM serial driver implementation. + * + * @author mike wakerly (opensource@hoho.com) + * @see Universal + * Serial Bus Class Definitions for Communication Devices, v1.1 + */ +public class CdcAcmSerialDriver extends CommonUsbSerialDriver { + + private final String TAG = CdcAcmSerialDriver.class.getSimpleName(); + + private final boolean mEnableAsyncReads; + private UsbInterface mControlInterface; + private UsbInterface mDataInterface; + + private UsbEndpoint mControlEndpoint; + private UsbEndpoint mReadEndpoint; + private UsbEndpoint mWriteEndpoint; + + private boolean mRts = false; + private boolean mDtr = false; + + private static final int USB_RECIP_INTERFACE = 0x01; + private static final int USB_RT_ACM = UsbConstants.USB_TYPE_CLASS | USB_RECIP_INTERFACE; + + private static final int SET_LINE_CODING = 0x20; // USB CDC 1.1 section 6.2 + private static final int GET_LINE_CODING = 0x21; + private static final int SET_CONTROL_LINE_STATE = 0x22; + private static final int SEND_BREAK = 0x23; + + public CdcAcmSerialDriver(UsbDevice device, UsbDeviceConnection connection) { + super(device, connection); + mEnableAsyncReads = (Build.VERSION.SDK_INT >= Build.VERSION_CODES.JELLY_BEAN_MR1); + } + + @Override + public void open() throws IOException { + Log.d(TAG, "device " + mDevice); + mControlInterface = null; + mDataInterface = null; + mWriteEndpoint = null; + mReadEndpoint = null; + + // locate all needed interfaces + for(int i = 0; i < mDevice.getInterfaceCount();i++){ + UsbInterface iface = mDevice.getInterface(i); + + switch(iface.getInterfaceClass()){ + case UsbConstants.USB_CLASS_COMM: + mControlInterface = iface; + Log.d(TAG, "control iface=" + iface); + break; + case UsbConstants.USB_CLASS_CDC_DATA: + mDataInterface = iface; + Log.d(TAG, "data iface=" + iface); + break; + default: + Log.d(TAG, "skipping iface=" + iface); + break; + } + } + + // failback to the old way + if(mControlInterface == null) { + mControlInterface = mDevice.getInterface(0); + Log.d(TAG, "Failback: Control iface=" + mControlInterface); + } + + if (!mConnection.claimInterface(mControlInterface, true)) { + throw new IOException("Could not claim control interface."); + } + + mControlEndpoint = mControlInterface.getEndpoint(0); + Log.d(TAG, "Control endpoint: " + mControlEndpoint); + + + if(mDataInterface == null) { + mDataInterface = mDevice.getInterface(1); + Log.d(TAG, "Failback: data iface=" + mDataInterface); + } + + if (!mConnection.claimInterface(mDataInterface, true)) { + throw new IOException("Could not claim data interface."); + } + + for(int i = 0; i < mDataInterface.getEndpointCount(); i++) { + UsbEndpoint endpoint = mDataInterface.getEndpoint(i); + switch (endpoint.getDirection()) { + case UsbConstants.USB_DIR_OUT: + mWriteEndpoint = endpoint; + Log.d(TAG, "Write endpoint: " + mWriteEndpoint); + break; + case UsbConstants.USB_DIR_IN: + mReadEndpoint = endpoint; + Log.d(TAG, "Read endpoint: " + mReadEndpoint); + break; + } + } + + if(mReadEndpoint == null || mWriteEndpoint == null){ + // failback to the old method + mReadEndpoint = mDataInterface.getEndpoint(0); + Log.d(TAG, "Read endpoint direction: " + mReadEndpoint.getDirection()); + mWriteEndpoint = mDataInterface.getEndpoint(1); + Log.d(TAG, "Write endpoint direction: " + mWriteEndpoint.getDirection()); + } + } + + + private int sendAcmControlMessage(int request, int value, byte[] buf) { + return mConnection.controlTransfer( + USB_RT_ACM, request, value, 0, buf, buf != null ? buf.length : 0, 5000); + } + + @Override + public void close() throws IOException { + mConnection.close(); + } + + @Override + public int read(byte[] dest, int timeoutMillis) throws IOException { + final int numBytesRead; + synchronized (mReadBufferLock) { + int readAmt = Math.min(dest.length, mReadBuffer.length); + numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer, readAmt, + timeoutMillis); + if (numBytesRead < 0) { + // This sucks: we get -1 on timeout, not 0 as preferred. + // We *should* use UsbRequest, except it has a bug/api oversight + // where there is no way to determine the number of bytes read + // in response :\ -- http://b.android.com/28023 + return 0; + } + System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead); + } + return numBytesRead; + } + + @Override + public int write(byte[] src, int timeoutMillis) throws IOException { + // TODO(mikey): Nearly identical to FtdiSerial write. Refactor. + int offset = 0; + + while (offset < src.length) { + final int writeLength; + final int amtWritten; + + synchronized (mWriteBufferLock) { + final byte[] writeBuffer; + + writeLength = Math.min(src.length - offset, mWriteBuffer.length); + if (offset == 0) { + writeBuffer = src; + } else { + // bulkTransfer does not support offsets, make a copy. + System.arraycopy(src, offset, mWriteBuffer, 0, writeLength); + writeBuffer = mWriteBuffer; + } + + amtWritten = mConnection.bulkTransfer(mWriteEndpoint, writeBuffer, writeLength, + timeoutMillis); + } + if (amtWritten <= 0) { + throw new IOException("Error writing " + writeLength + + " bytes at offset " + offset + " length=" + src.length); + } + + //Log.d(TAG, "Wrote amt=" + amtWritten + " attempted=" + writeLength); + offset += amtWritten; + } + return offset; + } + + @Override + public void setParameters(int baudRate, int dataBits, int stopBits, int parity) { + byte stopBitsByte; + switch (stopBits) { + case STOPBITS_1: stopBitsByte = 0; break; + case STOPBITS_1_5: stopBitsByte = 1; break; + case STOPBITS_2: stopBitsByte = 2; break; + default: throw new IllegalArgumentException("Bad value for stopBits: " + stopBits); + } + + byte parityBitesByte; + switch (parity) { + case PARITY_NONE: parityBitesByte = 0; break; + case PARITY_ODD: parityBitesByte = 1; break; + case PARITY_EVEN: parityBitesByte = 2; break; + case PARITY_MARK: parityBitesByte = 3; break; + case PARITY_SPACE: parityBitesByte = 4; break; + default: throw new IllegalArgumentException("Bad value for parity: " + parity); + } + + byte[] msg = { + (byte) ( baudRate & 0xff), + (byte) ((baudRate >> 8 ) & 0xff), + (byte) ((baudRate >> 16) & 0xff), + (byte) ((baudRate >> 24) & 0xff), + stopBitsByte, + parityBitesByte, + (byte) dataBits}; + sendAcmControlMessage(SET_LINE_CODING, 0, msg); + } + + @Override + public boolean getCD() throws IOException { + return false; // TODO + } + + @Override + public boolean getCTS() throws IOException { + return false; // TODO + } + + @Override + public boolean getDSR() throws IOException { + return false; // TODO + } + + @Override + public boolean getDTR() throws IOException { + return mDtr; + } + + @Override + public void setDTR(boolean value) throws IOException { + mDtr = value; + setDtrRts(); + } + + @Override + public boolean getRI() throws IOException { + return false; // TODO + } + + @Override + public boolean getRTS() throws IOException { + return mRts; + } + + @Override + public void setRTS(boolean value) throws IOException { + mRts = value; + setDtrRts(); + } + + private void setDtrRts() { + int value = (mRts ? 0x2 : 0) | (mDtr ? 0x1 : 0); + sendAcmControlMessage(SET_CONTROL_LINE_STATE, value, null); + } + + public static SparseArray getSupportedDevices() { + final SparseArray supportedDevices = new SparseArray(11); + supportedDevices.put(UsbId.VENDOR_ARDUINO, + new int[] { + UsbId.ARDUINO_UNO, + UsbId.ARDUINO_UNO_R3, + UsbId.ARDUINO_MEGA_2560, + UsbId.ARDUINO_MEGA_2560_R3, + UsbId.ARDUINO_SERIAL_ADAPTER, + UsbId.ARDUINO_SERIAL_ADAPTER_R3, + UsbId.ARDUINO_MEGA_ADK, + UsbId.ARDUINO_MEGA_ADK_R3, + UsbId.ARDUINO_LEONARDO, + }); + supportedDevices.put(UsbId.VENDOR_VAN_OOIJEN_TECH, + new int[] { + UsbId.VAN_OOIJEN_TECH_TEENSYDUINO_SERIAL, + }); + supportedDevices.put(UsbId.VENDOR_ATMEL, + new int[] { + UsbId.ATMEL_LUFA_CDC_DEMO_APP, + }); + supportedDevices.put(UsbId.VENDOR_LEAFLABS, + new int[] { + UsbId.LEAFLABS_MAPLE, + }); + supportedDevices.put(UsbId.VENDOR_ARDUINO2, + new int[] { + UsbId.VAN_OOIJEN_TECH_TEENSYDUINO_SERIAL, + UsbId.PIXHAWK, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_PX4), + new int[] { + UsbId.DEVICE_PX4FMU, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_UBLOX), + new int[] { + UsbId.DEVICE_UBLOX_5, + UsbId.DEVICE_UBLOX_6, + UsbId.DEVICE_UBLOX_7, + UsbId.DEVICE_UBLOX_8, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_OPENPILOT), + new int[] { + UsbId.DEVICE_CC3D, + UsbId.DEVICE_REVOLUTION, + UsbId.DEVICE_SPARKY2, + UsbId.DEVICE_OPLINK, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ARDUPILOT_CHIBIOS1), + new int[] { + UsbId.DEVICE_ARDUPILOT_CHIBIOS, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_ARDUPILOT_CHIBIOS2), + new int[] { + UsbId.DEVICE_ARDUPILOT_CHIBIOS, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_DRAGONLINK), + new int[] { + UsbId.DEVICE_DRAGONLINK, + }); + supportedDevices.put(Integer.valueOf(UsbId.VENDOR_RADIOLINK_MINI), + new int[] { + UsbId.DEVICE_RADIOLINK_MINI, + }); + return supportedDevices; + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java new file mode 100644 index 0000000000..9aff58843c --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/CommonUsbSerialDriver.java @@ -0,0 +1,137 @@ +/* Copyright 2013 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ + +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; + +import java.io.IOException; + +/** + * A base class shared by several driver implementations. + * + * @author mike wakerly (opensource@hoho.com) + */ +abstract class CommonUsbSerialDriver implements UsbSerialDriver { + + public static final int DEFAULT_READ_BUFFER_SIZE = 16 * 1024; + public static final int DEFAULT_WRITE_BUFFER_SIZE = 16 * 1024; + + protected final UsbDevice mDevice; + protected final UsbDeviceConnection mConnection; + + protected final Object mReadBufferLock = new Object(); + protected final Object mWriteBufferLock = new Object(); + + /** Internal read buffer. Guarded by {@link #mReadBufferLock}. */ + protected byte[] mReadBuffer; + + /** Internal write buffer. Guarded by {@link #mWriteBufferLock}. */ + protected byte[] mWriteBuffer; + + public CommonUsbSerialDriver(UsbDevice device, UsbDeviceConnection connection) { + mDevice = device; + mConnection = connection; + + mReadBuffer = new byte[DEFAULT_READ_BUFFER_SIZE]; + mWriteBuffer = new byte[DEFAULT_WRITE_BUFFER_SIZE]; + } + + /** + * Returns the currently-bound USB device. + * + * @return the device + */ + public final UsbDevice getDevice() { + return mDevice; + } + + /** + * Sets the size of the internal buffer used to exchange data with the USB + * stack for read operations. Most users should not need to change this. + * + * @param bufferSize the size in bytes + */ + public final void setReadBufferSize(int bufferSize) { + synchronized (mReadBufferLock) { + if (bufferSize == mReadBuffer.length) { + return; + } + mReadBuffer = new byte[bufferSize]; + } + } + + /** + * Sets the size of the internal buffer used to exchange data with the USB + * stack for write operations. Most users should not need to change this. + * + * @param bufferSize the size in bytes + */ + public final void setWriteBufferSize(int bufferSize) { + synchronized (mWriteBufferLock) { + if (bufferSize == mWriteBuffer.length) { + return; + } + mWriteBuffer = new byte[bufferSize]; + } + } + + @Override + public abstract void open() throws IOException; + + @Override + public abstract void close() throws IOException; + + @Override + public abstract int read(final byte[] dest, final int timeoutMillis) throws IOException; + + @Override + public abstract int write(final byte[] src, final int timeoutMillis) throws IOException; + + @Override + public abstract void setParameters( + int baudRate, int dataBits, int stopBits, int parity) throws IOException; + + @Override + public abstract boolean getCD() throws IOException; + + @Override + public abstract boolean getCTS() throws IOException; + + @Override + public abstract boolean getDSR() throws IOException; + + @Override + public abstract boolean getDTR() throws IOException; + + @Override + public abstract void setDTR(boolean value) throws IOException; + + @Override + public abstract boolean getRI() throws IOException; + + @Override + public abstract boolean getRTS() throws IOException; + + @Override + public abstract void setRTS(boolean value) throws IOException; + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java new file mode 100644 index 0000000000..0cd7b55a88 --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/Cp2102SerialDriver.java @@ -0,0 +1,276 @@ +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbConstants; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbInterface; +import android.util.Log; +import android.util.SparseArray; + +import java.io.IOException; +import java.util.LinkedHashMap; +import java.util.Map; + +public class Cp2102SerialDriver extends CommonUsbSerialDriver { + + private static final String TAG = Cp2102SerialDriver.class.getSimpleName(); + + private static final int DEFAULT_BAUD_RATE = 9600; + + private static final int USB_WRITE_TIMEOUT_MILLIS = 5000; + + /* + * Configuration Request Types + */ + private static final int REQTYPE_HOST_TO_DEVICE = 0x41; + + /* + * Configuration Request Codes + */ + private static final int SILABSER_IFC_ENABLE_REQUEST_CODE = 0x00; + private static final int SILABSER_SET_BAUDDIV_REQUEST_CODE = 0x01; + private static final int SILABSER_SET_LINE_CTL_REQUEST_CODE = 0x03; + private static final int SILABSER_SET_MHS_REQUEST_CODE = 0x07; + private static final int SILABSER_SET_BAUDRATE = 0x1E; + + /* + * SILABSER_IFC_ENABLE_REQUEST_CODE + */ + private static final int UART_ENABLE = 0x0001; + private static final int UART_DISABLE = 0x0000; + + /* + * SILABSER_SET_BAUDDIV_REQUEST_CODE + */ + private static final int BAUD_RATE_GEN_FREQ = 0x384000; + + /* + * SILABSER_SET_MHS_REQUEST_CODE + */ + private static final int MCR_DTR = 0x0001; + private static final int MCR_RTS = 0x0002; + private static final int MCR_ALL = 0x0003; + + private static final int CONTROL_WRITE_DTR = 0x0100; + private static final int CONTROL_WRITE_RTS = 0x0200; + + private UsbEndpoint mReadEndpoint; + private UsbEndpoint mWriteEndpoint; + + public Cp2102SerialDriver(UsbDevice device, UsbDeviceConnection connection) { + super(device, connection); + } + + private int setConfigSingle(int request, int value) { + return mConnection.controlTransfer(REQTYPE_HOST_TO_DEVICE, request, value, + 0, null, 0, USB_WRITE_TIMEOUT_MILLIS); + } + + @Override + public void open() throws IOException { + boolean opened = false; + try { + for (int i = 0; i < mDevice.getInterfaceCount(); i++) { + UsbInterface usbIface = mDevice.getInterface(i); + if (mConnection.claimInterface(usbIface, true)) { + Log.d(TAG, "claimInterface " + i + " SUCCESS"); + } else { + Log.d(TAG, "claimInterface " + i + " FAIL"); + } + } + + UsbInterface dataIface = mDevice.getInterface(mDevice.getInterfaceCount() - 1); + for (int i = 0; i < dataIface.getEndpointCount(); i++) { + UsbEndpoint ep = dataIface.getEndpoint(i); + if (ep.getType() == UsbConstants.USB_ENDPOINT_XFER_BULK) { + if (ep.getDirection() == UsbConstants.USB_DIR_IN) { + mReadEndpoint = ep; + } else { + mWriteEndpoint = ep; + } + } + } + + setConfigSingle(SILABSER_IFC_ENABLE_REQUEST_CODE, UART_ENABLE); + setConfigSingle(SILABSER_SET_MHS_REQUEST_CODE, MCR_ALL | CONTROL_WRITE_DTR | CONTROL_WRITE_RTS); + setConfigSingle(SILABSER_SET_BAUDDIV_REQUEST_CODE, BAUD_RATE_GEN_FREQ / DEFAULT_BAUD_RATE); +// setParameters(DEFAULT_BAUD_RATE, DEFAULT_DATA_BITS, DEFAULT_STOP_BITS, DEFAULT_PARITY); + opened = true; + } finally { + if (!opened) { + close(); + } + } + } + + @Override + public void close() throws IOException { + setConfigSingle(SILABSER_IFC_ENABLE_REQUEST_CODE, UART_DISABLE); + mConnection.close(); + } + + @Override + public int read(byte[] dest, int timeoutMillis) throws IOException { + final int numBytesRead; + synchronized (mReadBufferLock) { + int readAmt = Math.min(dest.length, mReadBuffer.length); + numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer, readAmt, + timeoutMillis); + if (numBytesRead < 0) { + // This sucks: we get -1 on timeout, not 0 as preferred. + // We *should* use UsbRequest, except it has a bug/api oversight + // where there is no way to determine the number of bytes read + // in response :\ -- http://b.android.com/28023 + return 0; + } + System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead); + } + return numBytesRead; + } + + @Override + public int write(byte[] src, int timeoutMillis) throws IOException { + int offset = 0; + + while (offset < src.length) { + final int writeLength; + final int amtWritten; + + synchronized (mWriteBufferLock) { + final byte[] writeBuffer; + + writeLength = Math.min(src.length - offset, mWriteBuffer.length); + if (offset == 0) { + writeBuffer = src; + } else { + // bulkTransfer does not support offsets, make a copy. + System.arraycopy(src, offset, mWriteBuffer, 0, writeLength); + writeBuffer = mWriteBuffer; + } + + amtWritten = mConnection.bulkTransfer(mWriteEndpoint, writeBuffer, writeLength, + timeoutMillis); + } + if (amtWritten <= 0) { + throw new IOException("Error writing " + writeLength + + " bytes at offset " + offset + " length=" + src.length); + } + + //Log.d(TAG, "Wrote amt=" + amtWritten + " attempted=" + writeLength); + offset += amtWritten; + } + return offset; + } + + private void setBaudRate(int baudRate) throws IOException { + byte[] data = new byte[] { + (byte) ( baudRate & 0xff), + (byte) ((baudRate >> 8 ) & 0xff), + (byte) ((baudRate >> 16) & 0xff), + (byte) ((baudRate >> 24) & 0xff) + }; + int ret = mConnection.controlTransfer(REQTYPE_HOST_TO_DEVICE, SILABSER_SET_BAUDRATE, + 0, 0, data, 4, USB_WRITE_TIMEOUT_MILLIS); + if (ret < 0) { + throw new IOException("Error setting baud rate."); + } + } + + @Override + public void setParameters(int baudRate, int dataBits, int stopBits, int parity) + throws IOException { + setBaudRate(baudRate); + + int configDataBits = 0; + switch (dataBits) { + case DATABITS_5: + configDataBits |= 0x0500; + break; + case DATABITS_6: + configDataBits |= 0x0600; + break; + case DATABITS_7: + configDataBits |= 0x0700; + break; + case DATABITS_8: + configDataBits |= 0x0800; + break; + default: + configDataBits |= 0x0800; + break; + } + setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configDataBits); + + int configParityBits = 0; // PARITY_NONE + switch (parity) { + case PARITY_ODD: + configParityBits |= 0x0010; + break; + case PARITY_EVEN: + configParityBits |= 0x0020; + break; + } + setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configParityBits); + + int configStopBits = 0; + switch (stopBits) { + case STOPBITS_1: + configStopBits |= 0; + break; + case STOPBITS_2: + configStopBits |= 2; + break; + } + setConfigSingle(SILABSER_SET_LINE_CTL_REQUEST_CODE, configStopBits); + } + + @Override + public boolean getCD() throws IOException { + return false; + } + + @Override + public boolean getCTS() throws IOException { + return false; + } + + @Override + public boolean getDSR() throws IOException { + return false; + } + + @Override + public boolean getDTR() throws IOException { + return true; + } + + @Override + public void setDTR(boolean value) throws IOException { + } + + @Override + public boolean getRI() throws IOException { + return false; + } + + @Override + public boolean getRTS() throws IOException { + return true; + } + + @Override + public void setRTS(boolean value) throws IOException { + } + + public static SparseArray getSupportedDevices() { + final SparseArray supportedDevices = new SparseArray(1); + supportedDevices.put(UsbId.VENDOR_SILAB, + new int[] { + UsbId.SILAB_CP2102 + }); + return supportedDevices; + } + + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/FtdiSerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/FtdiSerialDriver.java new file mode 100644 index 0000000000..c54d848b65 --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/FtdiSerialDriver.java @@ -0,0 +1,527 @@ +/* Copyright 2011 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ + +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbConstants; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbRequest; +import android.util.Log; +import android.util.SparseArray; + +import com.hoho.android.usbserial.util.HexDump; + +import java.io.IOException; +import java.nio.ByteBuffer; +import java.util.LinkedHashMap; +import java.util.Map; + +/** + * A {@link CommonUsbSerialDriver} implementation for a variety of FTDI devices + *

+ * This driver is based on + * libftdi, and is + * copyright and subject to the following terms: + * + *

+ *   Copyright (C) 2003 by Intra2net AG
+ *
+ *   This program is free software; you can redistribute it and/or modify
+ *   it under the terms of the GNU Lesser General Public License
+ *   version 2.1 as published by the Free Software Foundation;
+ *
+ *   opensource@intra2net.com
+ *   http://www.intra2net.com/en/developer/libftdi
+ * 
+ * + *

+ *

+ * Some FTDI devices have not been tested; see later listing of supported and + * unsupported devices. Devices listed as "supported" support the following + * features: + *

    + *
  • Read and write of serial data (see {@link #read(byte[], int)} and + * {@link #write(byte[], int)}. + *
  • Setting baud rate (see {@link #setBaudRate(int)}). + *
+ *

+ *

+ * Supported and tested devices: + *

    + *
  • {@value DeviceType#TYPE_R}
  • + *
+ *

+ *

+ * Unsupported but possibly working devices (please contact the author with + * feedback or patches): + *

    + *
  • {@value DeviceType#TYPE_2232C}
  • + *
  • {@value DeviceType#TYPE_2232H}
  • + *
  • {@value DeviceType#TYPE_4232H}
  • + *
  • {@value DeviceType#TYPE_AM}
  • + *
  • {@value DeviceType#TYPE_BM}
  • + *
+ *

+ * + * @author mike wakerly (opensource@hoho.com) + * @see USB Serial + * for Android project page + * @see FTDI Homepage + * @see libftdi + */ +public class FtdiSerialDriver extends CommonUsbSerialDriver { + + public static final int USB_TYPE_STANDARD = 0x00 << 5; + public static final int USB_TYPE_CLASS = 0x00 << 5; + public static final int USB_TYPE_VENDOR = 0x00 << 5; + public static final int USB_TYPE_RESERVED = 0x00 << 5; + + public static final int USB_RECIP_DEVICE = 0x00; + public static final int USB_RECIP_INTERFACE = 0x01; + public static final int USB_RECIP_ENDPOINT = 0x02; + public static final int USB_RECIP_OTHER = 0x03; + + public static final int USB_ENDPOINT_IN = 0x80; + public static final int USB_ENDPOINT_OUT = 0x00; + + public static final int USB_WRITE_TIMEOUT_MILLIS = 5000; + public static final int USB_READ_TIMEOUT_MILLIS = 5000; + + // From ftdi.h + /** + * Reset the port. + */ + private static final int SIO_RESET_REQUEST = 0; + + /** + * Set the modem control register. + */ + private static final int SIO_MODEM_CTRL_REQUEST = 1; + + /** + * Set flow control register. + */ + private static final int SIO_SET_FLOW_CTRL_REQUEST = 2; + + /** + * Set baud rate. + */ + private static final int SIO_SET_BAUD_RATE_REQUEST = 3; + + /** + * Set the data characteristics of the port. + */ + private static final int SIO_SET_DATA_REQUEST = 4; + + private static final int SIO_RESET_SIO = 0; + + public static final int FTDI_DEVICE_OUT_REQTYPE = + UsbConstants.USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_ENDPOINT_OUT; + + public static final int FTDI_DEVICE_IN_REQTYPE = + UsbConstants.USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_ENDPOINT_IN; + + /** + * Length of the modem status header, transmitted with every read. + */ + private static final int MODEM_STATUS_HEADER_LENGTH = 2; + + private final String TAG = FtdiSerialDriver.class.getSimpleName(); + + private DeviceType mType; + + /** + * FTDI chip types. + */ + private static enum DeviceType { + TYPE_BM, TYPE_AM, TYPE_2232C, TYPE_R, TYPE_2232H, TYPE_4232H + } + + private int mInterface = 0; /* INTERFACE_ANY */ + + private int mMaxPacketSize = 64; // TODO(mikey): detect + + /** + * Due to http://b.android.com/28023 , we cannot use UsbRequest async reads + * since it gives no indication of number of bytes read. Set this to + * {@code true} on platforms where it is fixed. + */ + private static final boolean ENABLE_ASYNC_READS = false; + + /** + * Filter FTDI status bytes from buffer + * @param src The source buffer (which contains status bytes) + * @param dest The destination buffer to write the status bytes into (can be src) + * @param totalBytesRead Number of bytes read to src + * @param maxPacketSize The USB endpoint max packet size + * @return The number of payload bytes + */ + private final int filterStatusBytes(byte[] src, byte[] dest, int totalBytesRead, int maxPacketSize) { + final int packetsCount = totalBytesRead / maxPacketSize + 1; + for (int packetIdx = 0; packetIdx < packetsCount; ++packetIdx) { + final int count = (packetIdx == (packetsCount - 1)) + ? (totalBytesRead % maxPacketSize) - MODEM_STATUS_HEADER_LENGTH + : maxPacketSize - MODEM_STATUS_HEADER_LENGTH; + if (count > 0) { + System.arraycopy(src, + packetIdx * maxPacketSize + MODEM_STATUS_HEADER_LENGTH, + dest, + packetIdx * (maxPacketSize - MODEM_STATUS_HEADER_LENGTH), + count); + } + } + + return totalBytesRead - (packetsCount * 2); + } + + /** + * Constructor. + * + * @param usbDevice the {@link UsbDevice} to use + * @param usbConnection the {@link UsbDeviceConnection} to use + * @throws UsbSerialRuntimeException if the given device is incompatible + * with this driver + */ + public FtdiSerialDriver(UsbDevice usbDevice, UsbDeviceConnection usbConnection) { + super(usbDevice, usbConnection); + mType = null; + } + + public void reset() throws IOException { + int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, SIO_RESET_REQUEST, + SIO_RESET_SIO, 0 /* index */, null, 0, USB_WRITE_TIMEOUT_MILLIS); + if (result != 0) { + throw new IOException("Reset failed: result=" + result); + } + + // TODO(mikey): autodetect. + mType = DeviceType.TYPE_R; + } + + @Override + public void open() throws IOException { + boolean opened = false; + try { + for (int i = 0; i < mDevice.getInterfaceCount(); i++) { + if (mConnection.claimInterface(mDevice.getInterface(i), true)) { + Log.d(TAG, "claimInterface " + i + " SUCCESS"); + } else { + throw new IOException("Error claiming interface " + i); + } + } + reset(); + opened = true; + } finally { + if (!opened) { + close(); + } + } + } + + @Override + public void close() { + mConnection.close(); + } + + @Override + public int read(byte[] dest, int timeoutMillis) throws IOException { + final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(0); + + if (ENABLE_ASYNC_READS) { + final int readAmt; + synchronized (mReadBufferLock) { + // mReadBuffer is only used for maximum read size. + readAmt = Math.min(dest.length, mReadBuffer.length); + } + + final UsbRequest request = new UsbRequest(); + request.initialize(mConnection, endpoint); + + final ByteBuffer buf = ByteBuffer.wrap(dest); + if (!request.queue(buf, readAmt)) { + throw new IOException("Error queueing request."); + } + + final UsbRequest response = mConnection.requestWait(); + if (response == null) { + throw new IOException("Null response"); + } + + final int payloadBytesRead = buf.position() - MODEM_STATUS_HEADER_LENGTH; + if (payloadBytesRead > 0) { + Log.d(TAG, HexDump.dumpHexString(dest, 0, Math.min(32, dest.length))); + return payloadBytesRead; + } else { + return 0; + } + } else { + final int totalBytesRead; + + synchronized (mReadBufferLock) { + final int readAmt = Math.min(dest.length, mReadBuffer.length); + totalBytesRead = mConnection.bulkTransfer(endpoint, mReadBuffer, + readAmt, timeoutMillis); + + if (totalBytesRead < MODEM_STATUS_HEADER_LENGTH) { + throw new IOException("Expected at least " + MODEM_STATUS_HEADER_LENGTH + " bytes"); + } + + return filterStatusBytes(mReadBuffer, dest, totalBytesRead, endpoint.getMaxPacketSize()); + } + } + } + + @Override + public int write(byte[] src, int timeoutMillis) throws IOException { + final UsbEndpoint endpoint = mDevice.getInterface(0).getEndpoint(1); + int offset = 0; + + while (offset < src.length) { + final int writeLength; + final int amtWritten; + + synchronized (mWriteBufferLock) { + final byte[] writeBuffer; + + writeLength = Math.min(src.length - offset, mWriteBuffer.length); + if (offset == 0) { + writeBuffer = src; + } else { + // bulkTransfer does not support offsets, make a copy. + System.arraycopy(src, offset, mWriteBuffer, 0, writeLength); + writeBuffer = mWriteBuffer; + } + + amtWritten = mConnection.bulkTransfer(endpoint, writeBuffer, writeLength, + timeoutMillis); + } + + if (amtWritten <= 0) { + throw new IOException("Error writing " + writeLength + + " bytes at offset " + offset + " length=" + src.length); + } + + //Log.d(TAG, "Wrote amtWritten=" + amtWritten + " attempted=" + writeLength); + offset += amtWritten; + } + return offset; + } + + private int setBaudRate(int baudRate) throws IOException { + long[] vals = convertBaudrate(baudRate); + long actualBaudrate = vals[0]; + long index = vals[1]; + long value = vals[2]; + int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, + SIO_SET_BAUD_RATE_REQUEST, (int) value, (int) index, + null, 0, USB_WRITE_TIMEOUT_MILLIS); + if (result != 0) { + throw new IOException("Setting baudrate failed: result=" + result); + } + return (int) actualBaudrate; + } + + @Override + public void setParameters(int baudRate, int dataBits, int stopBits, int parity) + throws IOException { + setBaudRate(baudRate); + + int config = dataBits; + + switch (parity) { + case PARITY_NONE: + config |= (0x00 << 8); + break; + case PARITY_ODD: + config |= (0x01 << 8); + break; + case PARITY_EVEN: + config |= (0x02 << 8); + break; + case PARITY_MARK: + config |= (0x03 << 8); + break; + case PARITY_SPACE: + config |= (0x04 << 8); + break; + default: + throw new IllegalArgumentException("Unknown parity value: " + parity); + } + + switch (stopBits) { + case STOPBITS_1: + config |= (0x00 << 11); + break; + case STOPBITS_1_5: + config |= (0x01 << 11); + break; + case STOPBITS_2: + config |= (0x02 << 11); + break; + default: + throw new IllegalArgumentException("Unknown stopBits value: " + stopBits); + } + + int result = mConnection.controlTransfer(FTDI_DEVICE_OUT_REQTYPE, + SIO_SET_DATA_REQUEST, config, 0 /* index */, + null, 0, USB_WRITE_TIMEOUT_MILLIS); + if (result != 0) { + throw new IOException("Setting parameters failed: result=" + result); + } + } + + private long[] convertBaudrate(int baudrate) { + // TODO(mikey): Braindead transcription of libfti method. Clean up, + // using more idiomatic Java where possible. + int divisor = 24000000 / baudrate; + int bestDivisor = 0; + int bestBaud = 0; + int bestBaudDiff = 0; + int fracCode[] = { + 0, 3, 2, 4, 1, 5, 6, 7 + }; + + for (int i = 0; i < 2; i++) { + int tryDivisor = divisor + i; + int baudEstimate; + int baudDiff; + + if (tryDivisor <= 8) { + // Round up to minimum supported divisor + tryDivisor = 8; + } else if (mType != DeviceType.TYPE_AM && tryDivisor < 12) { + // BM doesn't support divisors 9 through 11 inclusive + tryDivisor = 12; + } else if (divisor < 16) { + // AM doesn't support divisors 9 through 15 inclusive + tryDivisor = 16; + } else { + if (mType == DeviceType.TYPE_AM) { + // TODO + } else { + if (tryDivisor > 0x1FFFF) { + // Round down to maximum supported divisor value (for + // BM) + tryDivisor = 0x1FFFF; + } + } + } + + // Get estimated baud rate (to nearest integer) + baudEstimate = (24000000 + (tryDivisor / 2)) / tryDivisor; + + // Get absolute difference from requested baud rate + if (baudEstimate < baudrate) { + baudDiff = baudrate - baudEstimate; + } else { + baudDiff = baudEstimate - baudrate; + } + + if (i == 0 || baudDiff < bestBaudDiff) { + // Closest to requested baud rate so far + bestDivisor = tryDivisor; + bestBaud = baudEstimate; + bestBaudDiff = baudDiff; + if (baudDiff == 0) { + // Spot on! No point trying + break; + } + } + } + + // Encode the best divisor value + long encodedDivisor = (bestDivisor >> 3) | (fracCode[bestDivisor & 7] << 14); + // Deal with special cases for encoded value + if (encodedDivisor == 1) { + encodedDivisor = 0; // 3000000 baud + } else if (encodedDivisor == 0x4001) { + encodedDivisor = 1; // 2000000 baud (BM only) + } + + // Split into "value" and "index" values + long value = encodedDivisor & 0xFFFF; + long index; + if (mType == DeviceType.TYPE_2232C || mType == DeviceType.TYPE_2232H + || mType == DeviceType.TYPE_4232H) { + index = (encodedDivisor >> 8) & 0xffff; + index &= 0xFF00; + index |= 0 /* TODO mIndex */; + } else { + index = (encodedDivisor >> 16) & 0xffff; + } + + // Return the nearest baud rate + return new long[] { + bestBaud, index, value + }; + } + + @Override + public boolean getCD() throws IOException { + return false; + } + + @Override + public boolean getCTS() throws IOException { + return false; + } + + @Override + public boolean getDSR() throws IOException { + return false; + } + + @Override + public boolean getDTR() throws IOException { + return false; + } + + @Override + public void setDTR(boolean value) throws IOException { + } + + @Override + public boolean getRI() throws IOException { + return false; + } + + @Override + public boolean getRTS() throws IOException { + return false; + } + + @Override + public void setRTS(boolean value) throws IOException { + } + + public static SparseArray getSupportedDevices() { + final SparseArray supportedDevices = new SparseArray(1); + supportedDevices.put(UsbId.VENDOR_FTDI, + new int[] { + UsbId.FTDI_FT232R, + UsbId.FTDI_FT231X, + UsbId.DEVICE_PIXHAWK_2_CUBE, + }); + return supportedDevices; + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/ProlificSerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/ProlificSerialDriver.java new file mode 100644 index 0000000000..06406b43f8 --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/ProlificSerialDriver.java @@ -0,0 +1,526 @@ +/* This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: https://github.com/mik3y/usb-serial-for-android + */ + +/* + * Added to DroidPlanner + * by Eric Day + * + * Ported to usb-serial-for-android + * by Felix Hädicke + * + * Based on the pyprolific driver written + * by Emmanuel Blot + * See https://github.com/eblot/pyftdi + */ + +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbConstants; +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbEndpoint; +import android.hardware.usb.UsbInterface; +import android.util.Log; +import android.util.SparseArray; + +import java.io.IOException; +import java.lang.reflect.Method; +import java.util.LinkedHashMap; +import java.util.Map; + +public class ProlificSerialDriver extends CommonUsbSerialDriver { + + private final String TAG = ProlificSerialDriver.class.getSimpleName(); + + private static final int USB_READ_TIMEOUT_MILLIS = 1000; + private static final int USB_WRITE_TIMEOUT_MILLIS = 5000; + + private static final int USB_RECIP_INTERFACE = 0x01; + + private static final int PROLIFIC_VENDOR_READ_REQUEST = 0x01; + private static final int PROLIFIC_VENDOR_WRITE_REQUEST = 0x01; + + private static final int PROLIFIC_VENDOR_OUT_REQTYPE = /*UsbConstants.USB_DIR_OUT + |*/ UsbConstants.USB_TYPE_VENDOR; + + private static final int PROLIFIC_VENDOR_IN_REQTYPE = UsbConstants.USB_DIR_IN + | UsbConstants.USB_TYPE_VENDOR; + + private static final int PROLIFIC_CTRL_OUT_REQTYPE = /*UsbConstants.USB_DIR_OUT + |*/ UsbConstants.USB_TYPE_CLASS | USB_RECIP_INTERFACE; + + private static final int WRITE_ENDPOINT = 0x02; + private static final int READ_ENDPOINT = 0x83; + private static final int INTERRUPT_ENDPOINT = 0x81; + + private static final int FLUSH_RX_REQUEST = 0x08; + private static final int FLUSH_TX_REQUEST = 0x09; + + private static final int SET_LINE_REQUEST = 0x20; + private static final int SET_CONTROL_REQUEST = 0x22; + + private static final int CONTROL_DTR = 0x01; + private static final int CONTROL_RTS = 0x02; + + private static final int STATUS_FLAG_CD = 0x01; + private static final int STATUS_FLAG_DSR = 0x02; + private static final int STATUS_FLAG_RI = 0x08; + private static final int STATUS_FLAG_CTS = 0x80; + + private static final int STATUS_BUFFER_SIZE = 10; + private static final int STATUS_BYTE_IDX = 8; + + private static final int DEVICE_TYPE_HX = 0; + private static final int DEVICE_TYPE_0 = 1; + private static final int DEVICE_TYPE_1 = 2; + + private int mDeviceType = DEVICE_TYPE_HX; + + private UsbEndpoint mReadEndpoint; + private UsbEndpoint mWriteEndpoint; + private UsbEndpoint mInterruptEndpoint; + + private int mControlLinesValue = 0; + + private int mBaudRate = -1, mDataBits = -1, mStopBits = -1, mParity = -1; + + private int mStatus = 0; + private volatile Thread mReadStatusThread = null; + private final Object mReadStatusThreadLock = new Object(); + boolean mStopReadStatusThread = false; + private IOException mReadStatusException = null; + + + public ProlificSerialDriver(UsbDevice device, UsbDeviceConnection connection) { + super(device, connection); + } + + public static SparseArray getSupportedDevices() { + final SparseArray supportedDevices = new SparseArray(1); + supportedDevices.put(UsbId.VENDOR_PROLIFIC, + new int[] { UsbId.PROLIFIC_PL2303, }); + return supportedDevices; + } + + private final byte[] inControlTransfer(int requestType, int request, + int value, int index, int length) throws IOException { + byte[] buffer = new byte[length]; + int result = mConnection.controlTransfer(requestType, request, value, + index, buffer, length, USB_READ_TIMEOUT_MILLIS); + if (result != length) { + throw new IOException( + String.format("ControlTransfer with value 0x%x failed: %d", + value, result)); + } + return buffer; + } + + private final void outControlTransfer(int requestType, int request, + int value, int index, byte[] data) throws IOException { + int length = (data == null) ? 0 : data.length; + int result = mConnection.controlTransfer(requestType, request, value, + index, data, length, USB_WRITE_TIMEOUT_MILLIS); + if (result != length) { + throw new IOException( + String.format("ControlTransfer with value 0x%x failed: %d", + value, result)); + } + } + + private final byte[] vendorIn(int value, int index, int length) + throws IOException { + return inControlTransfer(PROLIFIC_VENDOR_IN_REQTYPE, + PROLIFIC_VENDOR_READ_REQUEST, value, index, length); + } + + private final void vendorOut(int value, int index, byte[] data) + throws IOException { + outControlTransfer(PROLIFIC_VENDOR_OUT_REQTYPE, + PROLIFIC_VENDOR_WRITE_REQUEST, value, index, data); + } + + private void resetDevice() throws IOException { + purgeHwBuffers(true, true); + } + + private final void ctrlOut(int request, int value, int index, byte[] data) + throws IOException { + outControlTransfer(PROLIFIC_CTRL_OUT_REQTYPE, request, value, index, + data); + } + + private void doBlackMagic() throws IOException { + vendorIn(0x8484, 0, 1); + vendorOut(0x0404, 0, null); + vendorIn(0x8484, 0, 1); + vendorIn(0x8383, 0, 1); + vendorIn(0x8484, 0, 1); + vendorOut(0x0404, 1, null); + vendorIn(0x8484, 0, 1); + vendorIn(0x8383, 0, 1); + vendorOut(0, 1, null); + vendorOut(1, 0, null); + vendorOut(2, (mDeviceType == DEVICE_TYPE_HX) ? 0x44 : 0x24, null); + } + + private void setControlLines(int newControlLinesValue) throws IOException { + ctrlOut(SET_CONTROL_REQUEST, newControlLinesValue, 0, null); + mControlLinesValue = newControlLinesValue; + } + + private final void readStatusThreadFunction() { + try { + while (!mStopReadStatusThread) { + byte[] buffer = new byte[STATUS_BUFFER_SIZE]; + int readBytesCount = mConnection.bulkTransfer(mInterruptEndpoint, + buffer, + STATUS_BUFFER_SIZE, + 500); + if (readBytesCount > 0) { + if (readBytesCount == STATUS_BUFFER_SIZE) { + mStatus = buffer[STATUS_BYTE_IDX] & 0xff; + } else { + throw new IOException( + String.format("Invalid CTS / DSR / CD / RI status buffer received, expected %d bytes, but received %d", + STATUS_BUFFER_SIZE, + readBytesCount)); + } + } + } + } catch (IOException e) { + mReadStatusException = e; + } + } + + private final int getStatus() throws IOException { + if ((mReadStatusThread == null) && (mReadStatusException == null)) { + synchronized (mReadStatusThreadLock) { + if (mReadStatusThread == null) { + byte[] buffer = new byte[STATUS_BUFFER_SIZE]; + int readBytes = mConnection.bulkTransfer(mInterruptEndpoint, + buffer, + STATUS_BUFFER_SIZE, + 100); + if (readBytes != STATUS_BUFFER_SIZE) { + Log.w(TAG, "Could not read initial CTS / DSR / CD / RI status"); + } else { + mStatus = buffer[STATUS_BYTE_IDX] & 0xff; + } + + mReadStatusThread = new Thread(new Runnable() { + @Override + public void run() { + readStatusThreadFunction(); + } + }); + mReadStatusThread.setDaemon(true); + mReadStatusThread.start(); + } + } + } + + /* throw and clear an exception which occured in the status read thread */ + IOException readStatusException = mReadStatusException; + if (mReadStatusException != null) { + mReadStatusException = null; + throw readStatusException; + } + + return mStatus; + } + + private final boolean testStatusFlag(int flag) throws IOException { + return ((getStatus() & flag) == flag); + } + + @Override + public void open() throws IOException { + boolean opened = false; + try { + for (int i = 0; i < mDevice.getInterfaceCount(); i++) { + UsbInterface usbIface = mDevice.getInterface(i); + if (mConnection.claimInterface(usbIface, true)) { + Log.d(TAG, "claimInterface " + i + " SUCCESS"); + } + else { + Log.d(TAG, "claimInterface " + i + " FAIL"); + } + } + + UsbInterface dataIface = mDevice.getInterface(mDevice.getInterfaceCount() - 1); + for (int i = 0; i < dataIface.getEndpointCount(); i ++) { + UsbEndpoint ep = dataIface.getEndpoint(i); + + switch (ep.getAddress()) { + case READ_ENDPOINT: + mReadEndpoint = ep; + break; + + case WRITE_ENDPOINT: + mWriteEndpoint = ep; + break; + + case INTERRUPT_ENDPOINT: + mInterruptEndpoint = ep; + break; + } + } + + if (mDevice.getDeviceClass() == 0x02) { + mDeviceType = DEVICE_TYPE_0; + } else { + try { + Method getRawDescriptorsMethod + = mConnection.getClass().getMethod("getRawDescriptors"); + byte[] rawDescriptors + = (byte[]) getRawDescriptorsMethod.invoke(mConnection); + byte maxPacketSize0 = rawDescriptors[7]; + if (maxPacketSize0 == 64) { + mDeviceType = DEVICE_TYPE_HX; + } else if ((mDevice.getDeviceClass() == 0x00) + || (mDevice.getDeviceClass() == 0xff)) { + mDeviceType = DEVICE_TYPE_1; + } else { + Log.w(TAG, "Could not detect PL2303 subtype, " + + "Assuming that it is a HX device"); + mDeviceType = DEVICE_TYPE_HX; + } + } catch (NoSuchMethodException e) { + Log.w(TAG, "Method UsbDeviceConnection.getRawDescriptors, " + + "required for PL2303 subtype detection, not " + + "available! Assuming that it is a HX device"); + mDeviceType = DEVICE_TYPE_HX; + } catch (Exception e) { + Log.e(TAG, "An unexpected exception occured while trying " + + "to detect PL2303 subtype", e); + } + } + + setControlLines(mControlLinesValue); + resetDevice(); + + doBlackMagic(); + opened = true; + } finally { + if (!opened) { + close(); + } + } + } + + @Override + public void close() throws IOException { + try { + mStopReadStatusThread = true; + synchronized (mReadStatusThreadLock) { + if (mReadStatusThread != null) { + try { + mReadStatusThread.join(); + } catch (Exception e) { + Log.w(TAG, "An error occured while waiting for status read thread", e); + } + } + } + resetDevice(); + } finally { + mConnection.close(); + } + } + + @Override + public int read(byte[] dest, int timeoutMillis) throws IOException { + final int numBytesRead; + synchronized (mReadBufferLock) { + int readAmt = Math.min(dest.length, mReadBuffer.length); + numBytesRead = mConnection.bulkTransfer(mReadEndpoint, mReadBuffer, + readAmt, timeoutMillis); + if (numBytesRead < 0) { + return 0; + } + System.arraycopy(mReadBuffer, 0, dest, 0, numBytesRead); + } + + return numBytesRead; + } + + @Override + public int write(byte[] src, int timeoutMillis) throws IOException { + int offset = 0; + + while (offset < src.length) { + final int writeLength; + final int amtWritten; + + synchronized (mWriteBufferLock) { + final byte[] writeBuffer; + + writeLength = Math.min(src.length - offset, mWriteBuffer.length); + if (offset == 0) { + writeBuffer = src; + } else { + // bulkTransfer does not support offsets, make a copy. + System.arraycopy(src, offset, mWriteBuffer, 0, writeLength); + writeBuffer = mWriteBuffer; + } + + amtWritten = mConnection.bulkTransfer(mWriteEndpoint, + writeBuffer, writeLength, timeoutMillis); + } + + if (amtWritten <= 0) { + throw new IOException("Error writing " + writeLength + + " bytes at offset " + offset + " length=" + + src.length); + } + + offset += amtWritten; + } + return offset; + } + + @Override + public void setParameters(int baudRate, int dataBits, int stopBits, + int parity) throws IOException { + if ((mBaudRate == baudRate) && (mDataBits == dataBits) + && (mStopBits == stopBits) && (mParity == parity)) { + // Make sure no action is performed if there is nothing to change + return; + } + + byte[] lineRequestData = new byte[7]; + + lineRequestData[0] = (byte) (baudRate & 0xff); + lineRequestData[1] = (byte) ((baudRate >> 8) & 0xff); + lineRequestData[2] = (byte) ((baudRate >> 16) & 0xff); + lineRequestData[3] = (byte) ((baudRate >> 24) & 0xff); + + switch (stopBits) { + case STOPBITS_1: + lineRequestData[4] = 0; + break; + + case STOPBITS_1_5: + lineRequestData[4] = 1; + break; + + case STOPBITS_2: + lineRequestData[4] = 2; + break; + + default: + throw new IllegalArgumentException("Unknown stopBits value: " + stopBits); + } + + switch (parity) { + case PARITY_NONE: + lineRequestData[5] = 0; + break; + + case PARITY_ODD: + lineRequestData[5] = 1; + break; + + case PARITY_MARK: + lineRequestData[5] = 3; + break; + + case PARITY_SPACE: + lineRequestData[5] = 4; + break; + + default: + throw new IllegalArgumentException("Unknown parity value: " + parity); + } + + lineRequestData[6] = (byte) dataBits; + + ctrlOut(SET_LINE_REQUEST, 0, 0, lineRequestData); + + resetDevice(); + + mBaudRate = baudRate; + mDataBits = dataBits; + mStopBits = stopBits; + mParity = parity; + } + + @Override + public boolean getCD() throws IOException { + return testStatusFlag(STATUS_FLAG_CD); + } + + @Override + public boolean getCTS() throws IOException { + return testStatusFlag(STATUS_FLAG_CTS); + } + + @Override + public boolean getDSR() throws IOException { + return testStatusFlag(STATUS_FLAG_DSR); + } + + @Override + public boolean getDTR() throws IOException { + return ((mControlLinesValue & CONTROL_DTR) == CONTROL_DTR); + } + + @Override + public void setDTR(boolean value) throws IOException { + int newControlLinesValue; + if (value) { + newControlLinesValue = mControlLinesValue | CONTROL_DTR; + } else { + newControlLinesValue = mControlLinesValue & ~CONTROL_DTR; + } + setControlLines(newControlLinesValue); + } + + @Override + public boolean getRI() throws IOException { + return testStatusFlag(STATUS_FLAG_RI); + } + + @Override + public boolean getRTS() throws IOException { + return ((mControlLinesValue & CONTROL_RTS) == CONTROL_RTS); + } + + @Override + public void setRTS(boolean value) throws IOException { + int newControlLinesValue; + if (value) { + newControlLinesValue = mControlLinesValue | CONTROL_RTS; + } else { + newControlLinesValue = mControlLinesValue & ~CONTROL_RTS; + } + setControlLines(newControlLinesValue); + } + + public boolean purgeHwBuffers(boolean purgeReadBuffers, boolean purgeWriteBuffers) throws IOException { + if (purgeReadBuffers) { + vendorOut(FLUSH_RX_REQUEST, 0, null); + } + + if (purgeWriteBuffers) { + vendorOut(FLUSH_TX_REQUEST, 0, null); + } + + return purgeReadBuffers || purgeWriteBuffers; + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbId.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbId.java new file mode 100644 index 0000000000..2c3cddeeac --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbId.java @@ -0,0 +1,96 @@ +/* Copyright 2012 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ +package com.hoho.android.usbserial.driver; + +/** + * Registry of USB vendor/product ID constants. + * + * Culled from various sources; see + * usb.ids for one listing. + * + * @author mike wakerly (opensource@hoho.com) + */ +public final class UsbId { + + public static final int VENDOR_FTDI = 0x0403; + public static final int FTDI_FT232R = 0x6001; + public static final int FTDI_FT231X = 0x6015; + public static final int DEVICE_PIXHAWK_2_CUBE = 0x0016; + + public static final int VENDOR_PX4 = 0x26AC; + public static final int DEVICE_PX4FMU = 0x11; + + public static final int VENDOR_ATMEL = 0x03EB; + public static final int ATMEL_LUFA_CDC_DEMO_APP = 0x2044; + + public static final int VENDOR_ARDUINO = 0x2341; + public static final int VENDOR_ARDUINO2 = 0x26ac; + public static final int ARDUINO_UNO = 0x0001; + public static final int ARDUINO_MEGA_2560 = 0x0010; + public static final int ARDUINO_SERIAL_ADAPTER = 0x003b; + public static final int ARDUINO_MEGA_ADK = 0x003f; + public static final int ARDUINO_MEGA_2560_R3 = 0x0042; + public static final int ARDUINO_UNO_R3 = 0x0043; + public static final int ARDUINO_MEGA_ADK_R3 = 0x0044; + public static final int ARDUINO_SERIAL_ADAPTER_R3 = 0x0044; + public static final int ARDUINO_LEONARDO = 0x8036; + public static final int PIXHAWK = 0x0011; + + public static final int VENDOR_VAN_OOIJEN_TECH = 0x16c0; + public static final int VAN_OOIJEN_TECH_TEENSYDUINO_SERIAL = 0x0483; + + public static final int VENDOR_LEAFLABS = 0x1eaf; + public static final int LEAFLABS_MAPLE = 0x0004; + + public static final int VENDOR_SILAB = 0x10c4; + public static final int SILAB_CP2102 = 0xea60; + + public static final int VENDOR_PROLIFIC = 0x067b; + public static final int PROLIFIC_PL2303 = 0x2303; + + public static final int VENDOR_UBLOX = 0x1546; + public static final int DEVICE_UBLOX_5 = 0x01a5; + public static final int DEVICE_UBLOX_6 = 0x01a6; + public static final int DEVICE_UBLOX_7 = 0x01a7; + public static final int DEVICE_UBLOX_8 = 0x01a8; + + public static final int VENDOR_OPENPILOT = 0x20A0; + public static final int DEVICE_REVOLUTION = 0x415E; + public static final int DEVICE_OPLINK = 0x415C; + public static final int DEVICE_SPARKY2 = 0x41D0; + public static final int DEVICE_CC3D = 0x415D; + + public static final int VENDOR_ARDUPILOT_CHIBIOS1 = 0x0483; + public static final int VENDOR_ARDUPILOT_CHIBIOS2 = 0x1209; + public static final int DEVICE_ARDUPILOT_CHIBIOS = 0x5740; + + public static final int VENDOR_DRAGONLINK = 0x1fc9; + public static final int DEVICE_DRAGONLINK = 0x0083; + + public static final int VENDOR_RADIOLINK_MINI = 0x26ac; + public static final int DEVICE_RADIOLINK_MINI = 0x0016; + + + + private UsbId() { + throw new IllegalAccessError("Non-instantiable class."); + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialDriver.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialDriver.java new file mode 100644 index 0000000000..e0e13c0f5d --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialDriver.java @@ -0,0 +1,200 @@ +/* Copyright 2011 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ + +package com.hoho.android.usbserial.driver; + +import java.io.IOException; + +/** + * Driver interface for a USB serial device. + * + * @author mike wakerly (opensource@hoho.com) + */ +public interface UsbSerialDriver { + + /** 5 data bits. */ + public static final int DATABITS_5 = 5; + + /** 6 data bits. */ + public static final int DATABITS_6 = 6; + + /** 7 data bits. */ + public static final int DATABITS_7 = 7; + + /** 8 data bits. */ + public static final int DATABITS_8 = 8; + + /** No flow control. */ + public static final int FLOWCONTROL_NONE = 0; + + /** RTS/CTS input flow control. */ + public static final int FLOWCONTROL_RTSCTS_IN = 1; + + /** RTS/CTS output flow control. */ + public static final int FLOWCONTROL_RTSCTS_OUT = 2; + + /** XON/XOFF input flow control. */ + public static final int FLOWCONTROL_XONXOFF_IN = 4; + + /** XON/XOFF output flow control. */ + public static final int FLOWCONTROL_XONXOFF_OUT = 8; + + /** No parity. */ + public static final int PARITY_NONE = 0; + + /** Odd parity. */ + public static final int PARITY_ODD = 1; + + /** Even parity. */ + public static final int PARITY_EVEN = 2; + + /** Mark parity. */ + public static final int PARITY_MARK = 3; + + /** Space parity. */ + public static final int PARITY_SPACE = 4; + + /** 1 stop bit. */ + public static final int STOPBITS_1 = 1; + + /** 1.5 stop bits. */ + public static final int STOPBITS_1_5 = 3; + + /** 2 stop bits. */ + public static final int STOPBITS_2 = 2; + + /** + * Opens and initializes the device as a USB serial device. Upon success, + * caller must ensure that {@link #close()} is eventually called. + * + * @throws IOException on error opening or initializing the device. + */ + public void open() throws IOException; + + /** + * Closes the serial device. + * + * @throws IOException on error closing the device. + */ + public void close() throws IOException; + + /** + * Reads as many bytes as possible into the destination buffer. + * + * @param dest the destination byte buffer + * @param timeoutMillis the timeout for reading + * @return the actual number of bytes read + * @throws IOException if an error occurred during reading + */ + public int read(final byte[] dest, final int timeoutMillis) throws IOException; + + /** + * Writes as many bytes as possible from the source buffer. + * + * @param src the source byte buffer + * @param timeoutMillis the timeout for writing + * @return the actual number of bytes written + * @throws IOException if an error occurred during writing + */ + public int write(final byte[] src, final int timeoutMillis) throws IOException; + + /** + * Sets various serial port parameters. + * + * @param baudRate baud rate as an integer, for example {@code 115200}. + * @param dataBits one of {@link #DATABITS_5}, {@link #DATABITS_6}, + * {@link #DATABITS_7}, or {@link #DATABITS_8}. + * @param stopBits one of {@link #STOPBITS_1}, {@link #STOPBITS_1_5}, or + * {@link #STOPBITS_2}. + * @param parity one of {@link #PARITY_NONE}, {@link #PARITY_ODD}, + * {@link #PARITY_EVEN}, {@link #PARITY_MARK}, or + * {@link #PARITY_SPACE}. + * @throws IOException on error setting the port parameters + */ + public void setParameters( + int baudRate, int dataBits, int stopBits, int parity) throws IOException; + + /** + * Gets the CD (Carrier Detect) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getCD() throws IOException; + + /** + * Gets the CTS (Clear To Send) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getCTS() throws IOException; + + /** + * Gets the DSR (Data Set Ready) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getDSR() throws IOException; + + /** + * Gets the DTR (Data Terminal Ready) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getDTR() throws IOException; + + /** + * Sets the DTR (Data Terminal Ready) bit on the underlying UART, if + * supported. + * + * @param value the value to set + * @throws IOException if an error occurred during writing + */ + public void setDTR(boolean value) throws IOException; + + /** + * Gets the RI (Ring Indicator) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getRI() throws IOException; + + /** + * Gets the RTS (Request To Send) bit from the underlying UART. + * + * @return the current state, or {@code false} if not supported. + * @throws IOException if an error occurred during reading + */ + public boolean getRTS() throws IOException; + + /** + * Sets the RTS (Request To Send) bit on the underlying UART, if + * supported. + * + * @param value the value to set + * @throws IOException if an error occurred during writing + */ + public void setRTS(boolean value) throws IOException; + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialProber.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialProber.java new file mode 100644 index 0000000000..f1667e3010 --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialProber.java @@ -0,0 +1,305 @@ +/* Copyright 2011 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ + +package com.hoho.android.usbserial.driver; + +import android.hardware.usb.UsbDevice; +import android.hardware.usb.UsbDeviceConnection; +import android.hardware.usb.UsbManager; +import android.util.Log; +import android.util.SparseArray; +import android.util.SparseIntArray; + +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; +import java.util.Map; + +/** + * Helper class which finds compatible {@link UsbDevice}s and creates + * {@link UsbSerialDriver} instances. + * + *

+ * You don't need a Prober to use the rest of the library: it is perfectly + * acceptable to instantiate driver instances manually. The Prober simply + * provides convenience functions. + * + *

+ * For most drivers, the corresponding {@link #probe(UsbManager, UsbDevice)} + * method will either return an empty list (device unknown / unsupported) or a + * singleton list. However, multi-port drivers may return multiple instances. + * + * @author mike wakerly (opensource@hoho.com) + */ +public enum UsbSerialProber { + + // TODO(mikey): Too much boilerplate. + + /** + * Prober for {@link FtdiSerialDriver}. + * + * @see FtdiSerialDriver + */ + FTDI_SERIAL { + @Override + public List probe(final UsbManager manager, final UsbDevice usbDevice) { + if (!testIfSupported(usbDevice, FtdiSerialDriver.getSupportedDevices())) { + return Collections.emptyList(); + } + final UsbDeviceConnection connection = manager.hasPermission(usbDevice) + ? manager.openDevice(usbDevice) + : null; + if (connection == null) { + return Collections.emptyList(); + } + final UsbSerialDriver driver = new FtdiSerialDriver(usbDevice, connection); + return Collections.singletonList(driver); + } + + @Override + public SparseArray getSupportedDevices(){ + return FtdiSerialDriver.getSupportedDevices(); + } + }, + + CDC_ACM_SERIAL { + @Override + public List probe(UsbManager manager, UsbDevice usbDevice) { + if (!testIfSupported(usbDevice, CdcAcmSerialDriver.getSupportedDevices())) { + return Collections.emptyList(); + } + final UsbDeviceConnection connection = manager.hasPermission(usbDevice) + ? manager.openDevice(usbDevice) + : null; + if (connection == null) { + return Collections.emptyList(); + } + final UsbSerialDriver driver = new CdcAcmSerialDriver(usbDevice, connection); + return Collections.singletonList(driver); + } + + @Override + public SparseArray getSupportedDevices(){ + return CdcAcmSerialDriver.getSupportedDevices(); + } + }, + + SILAB_SERIAL { + @Override + public List probe(final UsbManager manager, final UsbDevice usbDevice) { + if (!testIfSupported(usbDevice, Cp2102SerialDriver.getSupportedDevices())) { + return Collections.emptyList(); + } + final UsbDeviceConnection connection = manager.hasPermission(usbDevice) + ? manager.openDevice(usbDevice) + : null; + if (connection == null) { + return Collections.emptyList(); + } + final UsbSerialDriver driver = new Cp2102SerialDriver(usbDevice, connection); + return Collections.singletonList(driver); + } + + @Override + public SparseArray getSupportedDevices(){ + return Cp2102SerialDriver.getSupportedDevices(); + } + }, + + PROLIFIC_SERIAL { + @Override + public List probe(final UsbManager manager, final UsbDevice usbDevice) { + if (!testIfSupported(usbDevice, ProlificSerialDriver.getSupportedDevices())) { + return Collections.emptyList(); + } + final UsbDeviceConnection connection = manager.hasPermission(usbDevice) + ? manager.openDevice(usbDevice) + : null; + if (connection == null) { + return Collections.emptyList(); + } + final UsbSerialDriver driver = new ProlificSerialDriver(usbDevice, connection); + return Collections.singletonList(driver); + } + + @Override + public SparseArray getSupportedDevices(){ + return ProlificSerialDriver.getSupportedDevices(); + } + }; + + /** + * Tests the supplied {@link UsbDevice} for compatibility with this enum + * member, returning one or more driver instances if compatible. + * + * @param manager the {@link UsbManager} to use + * @param usbDevice the raw {@link UsbDevice} to use + * @return zero or more {@link UsbSerialDriver}, depending on compatibility + * (never {@code null}). + */ + protected abstract List probe(final UsbManager manager, final UsbDevice usbDevice); + + protected abstract SparseArray getSupportedDevices(); + + /** + * Creates and returns a new {@link UsbSerialDriver} instance for the first + * compatible {@link UsbDevice} found on the bus. If none are found, + * returns {@code null}. + * + *

+ * The order of devices is undefined, therefore if there are multiple + * devices on the bus, the chosen device may not be predictable (clients + * should use {@link #findAllDevices(UsbManager)} instead). + * + * @param usbManager the {@link UsbManager} to use. + * @return the first available {@link UsbSerialDriver}, or {@code null} if + * none are available. + */ + public static UsbSerialDriver findFirstDevice(final UsbManager usbManager) { + for (final UsbDevice usbDevice : usbManager.getDeviceList().values()) { + for (final UsbSerialProber prober : values()) { + final List probedDevices = prober.probe(usbManager, usbDevice); + if (!probedDevices.isEmpty()) { + return probedDevices.get(0); + } + } + } + return null; + } + + public static UsbSerialDriver openUsbDevice(final UsbManager usbManager, + final UsbDevice device){ + for (final UsbSerialProber prober : values()) { + final List probedDevices = prober.probe(usbManager, device); + if (!probedDevices.isEmpty()) { + return probedDevices.get(0); + } + } + + return null; + } + + public static List getAvailableSupportedDevices(final UsbManager usbManager){ + List supportedDevices = new ArrayList(); + for(UsbDevice usbDevice: usbManager.getDeviceList().values()){ + for(UsbSerialProber prober: values()) { + if (testIfSupported(usbDevice, prober.getSupportedDevices())){ + supportedDevices.add(usbDevice); + break; + } + } + } + + return supportedDevices; + } + + /** + * Creates a new {@link UsbSerialDriver} instance for all compatible + * {@link UsbDevice}s found on the bus. If no compatible devices are found, + * the list will be empty. + * + * @param usbManager + * @return + */ + public static List findAllDevices(final UsbManager usbManager) { + final List result = new ArrayList(); + + // For each UsbDevice, call probe() for each prober. + for (final UsbDevice usbDevice : usbManager.getDeviceList().values()) { + result.addAll(probeSingleDevice(usbManager, usbDevice)); + } + return result; + } + + /** + * Special method for testing a specific device for driver support, + * returning any compatible driver(s). + * + *

+ * Clients should ordinarily use {@link #findAllDevices(UsbManager)}, which + * operates against the entire bus of devices. This method is useful when + * testing against only a single target is desired. + * + * @param usbManager the {@link UsbManager} to use. + * @param usbDevice the device to test against. + * @return a list containing zero or more {@link UsbSerialDriver} instances. + */ + public static List probeSingleDevice(final UsbManager usbManager, + UsbDevice usbDevice) { + final List result = new ArrayList(); + for (final UsbSerialProber prober : values()) { + final List probedDevices = prober.probe(usbManager, usbDevice); + result.addAll(probedDevices); + } + return result; + } + + /** + * Deprecated; Use {@link #findFirstDevice(UsbManager)}. + * + * @param usbManager + * @return + */ + @Deprecated + public static UsbSerialDriver acquire(final UsbManager usbManager) { + return findFirstDevice(usbManager); + } + + /** + * Deprecated; use {@link #probeSingleDevice(UsbManager, UsbDevice)}. + * + * @param usbManager + * @param usbDevice + * @return + */ + @Deprecated + public static UsbSerialDriver acquire(final UsbManager usbManager, final UsbDevice usbDevice) { + final List probedDevices = probeSingleDevice(usbManager, usbDevice); + if (!probedDevices.isEmpty()) { + return probedDevices.get(0); + } + return null; + } + + /** + * Returns {@code true} if the given device is found in the driver's + * vendor/product map. + * + * @param usbDevice the device to test + * @param supportedDevices map of vendor IDs to product ID(s) + * @return {@code true} if supported + */ + private static boolean testIfSupported(final UsbDevice usbDevice, + final SparseArray supportedDevices) { + final int[] supportedProducts = supportedDevices.get(usbDevice.getVendorId()); + if (supportedProducts == null) { + return false; + } + + final int productId = usbDevice.getProductId(); + for (int supportedProductId : supportedProducts) { + if (productId == supportedProductId) { + return true; + } + } + return false; + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java new file mode 100644 index 0000000000..b48607c59d --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/driver/UsbSerialRuntimeException.java @@ -0,0 +1,46 @@ +/* + * Copyright 2011 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + */ + +package com.hoho.android.usbserial.driver; + +/** + * Generic unchecked exception for the usbserial package. + * + * @author mike wakerly (opensource@hoho.com) + */ +@SuppressWarnings("serial") +public class UsbSerialRuntimeException extends RuntimeException { + + public UsbSerialRuntimeException() { + super(); + } + + public UsbSerialRuntimeException(String detailMessage, Throwable throwable) { + super(detailMessage, throwable); + } + + public UsbSerialRuntimeException(String detailMessage) { + super(detailMessage); + } + + public UsbSerialRuntimeException(Throwable throwable) { + super(throwable); + } + +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/util/HexDump.java b/ClientLib/src/main/java/com/hoho/android/usbserial/util/HexDump.java new file mode 100644 index 0000000000..54f6e4272e --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/util/HexDump.java @@ -0,0 +1,162 @@ +/* + * Copyright (C) 2006 The Android Open Source Project + * + * 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 + * + * http://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. + */ + +package com.hoho.android.usbserial.util; + +/** + * Clone of Android's HexDump class, for use in debugging. Cosmetic changes + * only. + */ +public class HexDump { + private final static char[] HEX_DIGITS = { + '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' + }; + + public static String dumpHexString(byte[] array) { + return dumpHexString(array, 0, array.length); + } + + public static String dumpHexString(byte[] array, int offset, int length) { + StringBuilder result = new StringBuilder(); + + byte[] line = new byte[16]; + int lineIndex = 0; + + result.append("\n0x"); + result.append(toHexString(offset)); + + for (int i = offset; i < offset + length; i++) { + if (lineIndex == 16) { + result.append(" "); + + for (int j = 0; j < 16; j++) { + if (line[j] > ' ' && line[j] < '~') { + result.append(new String(line, j, 1)); + } else { + result.append("."); + } + } + + result.append("\n0x"); + result.append(toHexString(i)); + lineIndex = 0; + } + + byte b = array[i]; + result.append(" "); + result.append(HEX_DIGITS[(b >>> 4) & 0x0F]); + result.append(HEX_DIGITS[b & 0x0F]); + + line[lineIndex++] = b; + } + + if (lineIndex != 16) { + int count = (16 - lineIndex) * 3; + count++; + for (int i = 0; i < count; i++) { + result.append(" "); + } + + for (int i = 0; i < lineIndex; i++) { + if (line[i] > ' ' && line[i] < '~') { + result.append(new String(line, i, 1)); + } else { + result.append("."); + } + } + } + + return result.toString(); + } + + public static String toHexString(byte b) { + return toHexString(toByteArray(b)); + } + + public static String toHexString(byte[] array) { + return toHexString(array, 0, array.length); + } + + public static String toHexString(byte[] array, int offset, int length) { + char[] buf = new char[length * 2]; + + int bufIndex = 0; + for (int i = offset; i < offset + length; i++) { + byte b = array[i]; + buf[bufIndex++] = HEX_DIGITS[(b >>> 4) & 0x0F]; + buf[bufIndex++] = HEX_DIGITS[b & 0x0F]; + } + + return new String(buf); + } + + public static String toHexString(int i) { + return toHexString(toByteArray(i)); + } + + public static String toHexString(short i) { + return toHexString(toByteArray(i)); + } + + public static byte[] toByteArray(byte b) { + byte[] array = new byte[1]; + array[0] = b; + return array; + } + + public static byte[] toByteArray(int i) { + byte[] array = new byte[4]; + + array[3] = (byte) (i & 0xFF); + array[2] = (byte) ((i >> 8) & 0xFF); + array[1] = (byte) ((i >> 16) & 0xFF); + array[0] = (byte) ((i >> 24) & 0xFF); + + return array; + } + + public static byte[] toByteArray(short i) { + byte[] array = new byte[2]; + + array[1] = (byte) (i & 0xFF); + array[0] = (byte) ((i >> 8) & 0xFF); + + return array; + } + + private static int toByte(char c) { + if (c >= '0' && c <= '9') + return (c - '0'); + if (c >= 'A' && c <= 'F') + return (c - 'A' + 10); + if (c >= 'a' && c <= 'f') + return (c - 'a' + 10); + + throw new RuntimeException("Invalid hex char '" + c + "'"); + } + + public static byte[] hexStringToByteArray(String hexString) { + int length = hexString.length(); + byte[] buffer = new byte[length / 2]; + + for (int i = 0; i < length; i += 2) { + buffer[i / 2] = (byte) ((toByte(hexString.charAt(i)) << 4) | toByte(hexString + .charAt(i + 1))); + } + + return buffer; + } +} diff --git a/ClientLib/src/main/java/com/hoho/android/usbserial/util/SerialInputOutputManager.java b/ClientLib/src/main/java/com/hoho/android/usbserial/util/SerialInputOutputManager.java new file mode 100644 index 0000000000..d0be45e96a --- /dev/null +++ b/ClientLib/src/main/java/com/hoho/android/usbserial/util/SerialInputOutputManager.java @@ -0,0 +1,189 @@ +/* Copyright 2011 Google Inc. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, + * USA. + * + * Project home page: http://code.google.com/p/usb-serial-for-android/ + */ + +package com.hoho.android.usbserial.util; + +import android.hardware.usb.UsbRequest; +import android.util.Log; + +import com.hoho.android.usbserial.driver.UsbSerialDriver; + +import java.io.IOException; +import java.nio.ByteBuffer; + +/** + * Utility class which services a {@link UsbSerialDriver} in its {@link #run()} + * method. + * + * @author mike wakerly (opensource@hoho.com) + */ +public class SerialInputOutputManager implements Runnable { + + private static final String TAG = SerialInputOutputManager.class.getSimpleName(); + private static final boolean DEBUG = true; + + private static final int READ_WAIT_MILLIS = 200; + private static final int BUFSIZ = 4096; + + private final UsbSerialDriver mDriver; + + private final ByteBuffer mReadBuffer = ByteBuffer.allocate(BUFSIZ); + + // Synchronized by 'mWriteBuffer' + private final ByteBuffer mWriteBuffer = ByteBuffer.allocate(BUFSIZ); + + private enum State { + STOPPED, + RUNNING, + STOPPING + } + + // Synchronized by 'this' + private State mState = State.STOPPED; + + // Synchronized by 'this' + private Listener mListener; + + public interface Listener { + /** + * Called when new incoming data is available. + */ + public void onNewData(byte[] data); + + /** + * Called when {@link SerialInputOutputManager#run()} aborts due to an + * error. + */ + public void onRunError(Exception e); + } + + /** + * Creates a new instance with no listener. + */ + public SerialInputOutputManager(UsbSerialDriver driver) { + this(driver, null); + } + + /** + * Creates a new instance with the provided listener. + */ + public SerialInputOutputManager(UsbSerialDriver driver, Listener listener) { + mDriver = driver; + mListener = listener; + } + + public synchronized void setListener(Listener listener) { + mListener = listener; + } + + public synchronized Listener getListener() { + return mListener; + } + + public void writeAsync(byte[] data) { + synchronized (mWriteBuffer) { + mWriteBuffer.put(data); + } + } + + public synchronized void stop() { + if (getState() == State.RUNNING) { + Log.i(TAG, "Stop requested"); + mState = State.STOPPING; + } + } + + private synchronized State getState() { + return mState; + } + + /** + * Continuously services the read and write buffers until {@link #stop()} is + * called, or until a driver exception is raised. + * + * NOTE(mikey): Uses inefficient read/write-with-timeout. + * TODO(mikey): Read asynchronously with {@link UsbRequest#queue(ByteBuffer, int)} + */ + @Override + public void run() { + synchronized (this) { + if (getState() != State.STOPPED) { + throw new IllegalStateException("Already running."); + } + mState = State.RUNNING; + } + + Log.i(TAG, "Running .."); + try { + while (true) { + if (getState() != State.RUNNING) { + Log.i(TAG, "Stopping mState=" + getState()); + break; + } + step(); + } + } catch (Exception e) { + Log.w(TAG, "Run ending due to exception: " + e.getMessage(), e); + final Listener listener = getListener(); + if (listener != null) { + listener.onRunError(e); + } + } finally { + synchronized (this) { + mState = State.STOPPED; + Log.i(TAG, "Stopped."); + } + } + } + + private void step() throws IOException { + // Handle incoming data. + int len = mDriver.read(mReadBuffer.array(), READ_WAIT_MILLIS); + if (len > 0) { + if (DEBUG) Log.d(TAG, "Read data len=" + len); + final Listener listener = getListener(); + if (listener != null) { + final byte[] data = new byte[len]; + mReadBuffer.get(data, 0, len); + listener.onNewData(data); + } + mReadBuffer.clear(); + } + + // Handle outgoing data. + byte[] outBuff = null; + synchronized (mWriteBuffer) { + if (mWriteBuffer.position() > 0) { + len = mWriteBuffer.position(); + outBuff = new byte[len]; + mWriteBuffer.rewind(); + mWriteBuffer.get(outBuff, 0, len); + mWriteBuffer.clear(); + } + } + if (outBuff != null) { + if (DEBUG) { + Log.d(TAG, "Writing data len=" + len); + } + mDriver.write(outBuff, READ_WAIT_MILLIS); + } + } + +} diff --git a/ClientLib/src/main/res/xml/device_filter.xml b/ClientLib/src/main/res/xml/device_filter.xml index 8f32775e98..f8e44e69f4 100644 --- a/ClientLib/src/main/res/xml/device_filter.xml +++ b/ClientLib/src/main/res/xml/device_filter.xml @@ -1,18 +1,49 @@ - - - - - - - - - - - - + + + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +